TransportIface.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GAZEBO_TRANSPORTIFACE_HH_
18 #define _GAZEBO_TRANSPORTIFACE_HH_
19 
20 #include <boost/bind.hpp>
21 #include <string>
22 #include <list>
23 #include <map>
24 
27 #include "gazebo/transport/Node.hh"
29 
30 namespace gazebo
31 {
32  namespace transport
33  {
37 
44  GZ_TRANSPORT_VISIBLE
45  bool get_master_uri(std::string &_master_host, unsigned int &_master_port);
46 
55  GZ_TRANSPORT_VISIBLE
56  bool init(const std::string &_masterHost = "",
57  unsigned int _masterPort = 0,
58  uint32_t _timeoutIterations = 30);
59 
63  GZ_TRANSPORT_VISIBLE
64  void run();
65 
68  GZ_TRANSPORT_VISIBLE
69  void get_topic_namespaces(std::list<std::string> &_namespaces);
70 
73  GZ_TRANSPORT_VISIBLE
74  bool is_stopped();
75 
77  GZ_TRANSPORT_VISIBLE
78  void stop();
79 
81  GZ_TRANSPORT_VISIBLE
82  void fini();
83 
85  GZ_TRANSPORT_VISIBLE
86  void clear_buffers();
87 
91  GZ_TRANSPORT_VISIBLE
92  void pause_incoming(bool _pause);
93 
103  GZ_TRANSPORT_VISIBLE
104  boost::shared_ptr<msgs::Response> request(const std::string &_worldName,
105  const std::string &_request,
106  const std::string &_data = "",
107  const common::Time &_timeout = -1);
108 
109 
116  GZ_TRANSPORT_VISIBLE
117  void requestNoReply(const std::string &_worldName,
118  const std::string &_request,
119  const std::string &_data = "");
120 
126  GZ_TRANSPORT_VISIBLE
127  void requestNoReply(NodePtr _node, const std::string &_request,
128  const std::string &_data = "");
129 
136  template<typename M>
137  void publish(const std::string &_topic,
138  const google::protobuf::Message &_message)
139  {
141  node->Init();
142  node->Publish<M>(_topic, _message);
143  }
144 
148  GZ_TRANSPORT_VISIBLE
149  std::map<std::string, std::list<std::string> > getAdvertisedTopics();
150 
156  GZ_TRANSPORT_VISIBLE
157  std::list<std::string> getAdvertisedTopics(const std::string &_msgType);
158 
162  GZ_TRANSPORT_VISIBLE
163  std::string getTopicMsgType(const std::string &_topicName);
164 
167  GZ_TRANSPORT_VISIBLE
168  void setMinimalComms(bool _enabled);
169 
172  GZ_TRANSPORT_VISIBLE
173  bool getMinimalComms();
174 
177  GZ_TRANSPORT_VISIBLE
179 
183  GZ_TRANSPORT_VISIBLE
184  bool waitForNamespaces(const gazebo::common::Time &_maxWait);
186  }
187 }
188 #endif
boost::shared_ptr< msgs::Response > request(const std::string &_worldName, const std::string &_request, const std::string &_data="", const common::Time &_timeout=-1)
Send a request and receive a response.
Forward declarations for the common classes.
Definition: Animation.hh:26
transport
Definition: ConnectionManager.hh:35
bool init(const std::string &_masterHost="", unsigned int _masterPort=0, uint32_t _timeoutIterations=30)
Initialize the transport system.
void run()
Run the transport component.
void pause_incoming(bool _pause)
Pause or unpause incoming messages.
void fini()
Cleanup the transport component.
Forward declarations for transport.
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
void stop()
Stop the transport component from running.
void setMinimalComms(bool _enabled)
Set whether minimal comms should be used.
boost::shared_ptr< Connection > ConnectionPtr
Definition: Connection.hh:51
std::string getTopicMsgType(const std::string &_topicName)
Get the message typename that is published on the given topic.
std::map< std::string, std::list< std::string > > getAdvertisedTopics()
Get a list of all the topics and their message types.
bool get_master_uri(std::string &_master_host, unsigned int &_master_port)
Get the hostname and port of the master from the GAZEBO_MASTER_URI environment variable.
A node can advertise and subscribe topics, publish on advertised topics and listen to subscribed topi...
Definition: Node.hh:78
void publish(const std::string &_topic, const google::protobuf::Message &_message)
A convenience function for a one-time publication of a message.
Definition: TransportIface.hh:137
transport::ConnectionPtr connectToMaster()
Create a connection to master.
bool is_stopped()
Is the transport system stopped?
void clear_buffers()
Clear any remaining communication buffers.
bool getMinimalComms()
Get whether minimal comms has been enabled.
bool waitForNamespaces(const gazebo::common::Time &_maxWait)
Blocks while waiting for topic namespaces from the Master.
void requestNoReply(const std::string &_worldName, const std::string &_request, const std::string &_data="")
Send a request and don&#39;t wait for a response.
void get_topic_namespaces(std::list< std::string > &_namespaces)
Return all the namespace (world names) on the master.
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:47