91 if (connection_header)
93 ros::M_string::const_iterator it = connection_header->find(
"latching");
94 if((it != connection_header->end()) && (it->second ==
"1"))
96 ROS_DEBUG(
"input topic is latched; latching output topic to match");
123 ROS_ERROR(
"Failed to communicate with rosmaster");
127 int subscriber_num = 0;
129 for (
int i = 0; i < sub_info.
size(); ++i)
131 string topic_name = sub_info[i][0];
134 for (
int j = 0; j < subscribers.
size(); ++j)
144 else if (!g_sub && subscriber_num > 0)
subscribe();
147 int main(
int argc,
char **argv)
151 printf(
"\nusage: relay IN_TOPIC [OUT_TOPIC]\n\n");
154 std::string topic_name;
157 ros::init(argc, argv, topic_name +
string(
"_relay"),
168 bool unreliable =
false;
169 pnh.
getParam(
"unreliable", unreliable);
179 pnh.
param<
double>(
"monitor_rate", monitor_rate, 1.0);
void in_cb(const ros::MessageEvent< ShapeShifter > &msg_event)
TransportHints & reliable()
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
const boost::shared_ptr< M_string > & getConnectionHeaderPtr() const
void timer_cb(const ros::TimerEvent &)
const boost::shared_ptr< ConstMessage > & getConstMessage() const
TransportHints & unreliable()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
int main(int argc, char **argv)
void conn_cb(const ros::SingleSubscriberPublisher &)
uint32_t getNumSubscribers() const
bool getParam(const std::string &key, std::string &s) const