topic_handlers.h
Go to the documentation of this file.
1 
35 #ifndef ROSSERIAL_SERVER_TOPIC_HANDLERS_H
36 #define ROSSERIAL_SERVER_TOPIC_HANDLERS_H
37 
38 #include <ros/ros.h>
39 #include <rosserial_msgs/TopicInfo.h>
42 
43 namespace rosserial_server
44 {
45 
46 class Publisher {
47 public:
48  Publisher(ros::NodeHandle& nh, const rosserial_msgs::TopicInfo& topic_info) {
50  try
51  {
52  msginfo = lookupMessage(topic_info.message_type);
53  }
54  catch (const std::exception& e)
55  {
56  ROS_WARN_STREAM("Unable to look up message: " << e.what());
57  }
58 
59  if (!msginfo.md5sum.empty() && msginfo.md5sum != topic_info.md5sum)
60  {
61  ROS_WARN_STREAM("Message" << topic_info.message_type << "MD5 sum from client does not "
62  "match that in system. Will avoid using system's message definition.");
63  msginfo.full_text = "";
64  }
65  message_.morph(topic_info.md5sum, topic_info.message_type, msginfo.full_text, "false");
66  publisher_ = message_.advertise(nh, topic_info.topic_name, 1);
67  }
68 
72  }
73 
74  std::string get_topic() {
75  return publisher_.getTopic();
76  }
77 
78 private:
81 };
82 
84 
85 
86 class Subscriber {
87 public:
88  Subscriber(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
89  boost::function<void(std::vector<uint8_t>& buffer)> write_fn)
90  : write_fn_(write_fn) {
93  topic_info.topic_name, 1, boost::bind(&Subscriber::handle, this, _1));
94  opts.md5sum = topic_info.md5sum;
95  opts.datatype = topic_info.message_type;
96  subscriber_ = nh.subscribe(opts);
97  }
98 
99  std::string get_topic() {
100  return subscriber_.getTopic();
101  }
102 
103 private:
105  size_t length = ros::serialization::serializationLength(*msg);
106  std::vector<uint8_t> buffer(length);
107 
108  ros::serialization::OStream ostream(&buffer[0], length);
110 
111  write_fn_(buffer);
112  }
113 
115  boost::function<void(std::vector<uint8_t>& buffer)> write_fn_;
116 };
117 
119 
121 public:
122  ServiceClient(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
123  boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn)
124  : write_fn_(write_fn) {
125  topic_id_ = -1;
126 
129  rosserial_server::MsgInfo respinfo;
130  try
131  {
132  srvinfo = lookupMessage(topic_info.message_type, "srv");
133  reqinfo = lookupMessage(topic_info.message_type + "Request", "srv");
134  respinfo = lookupMessage(topic_info.message_type + "Response", "srv");
135  }
136  catch (const std::exception& e)
137  {
138  ROS_WARN_STREAM("Unable to look up service definition: " << e.what());
139  }
140  service_md5_ = srvinfo.md5sum;
141  request_message_md5_ = reqinfo.md5sum;
142  response_message_md5_ = respinfo.md5sum;
143 
145  opts.service = topic_info.topic_name;
146  opts.md5sum = srvinfo.md5sum;
147  opts.persistent = false; // always false for now
148  service_client_ = nh.serviceClient(opts);
149  }
150  void setTopicId(uint16_t topic_id) {
151  topic_id_ = topic_id;
152  }
153  std::string getServiceMD5() {
154  return service_md5_;
155  }
156  std::string getRequestMessageMD5() {
157  return request_message_md5_;
158  }
159  std::string getResponseMessageMD5() {
160  return response_message_md5_;
161  }
162 
164  // deserialize request message
166 
167  // perform service call
168  // note that at present, at least for rosserial-windows a service call returns nothing,
169  // so we discard the return value of this call() invocation.
171 
172  // write service response over the wire
174  std::vector<uint8_t> buffer(length);
175  ros::serialization::OStream ostream(&buffer[0], length);
177  write_fn_(buffer,topic_id_);
178  }
179 
180 private:
184  boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn_;
185  std::string service_md5_;
186  std::string request_message_md5_;
188  uint16_t topic_id_;
189 };
190 
192 
193 } // namespace
194 
195 #endif // ROSSERIAL_SERVER_TOPIC_HANDLERS_H
rosserial_server::Publisher::Publisher
Publisher(ros::NodeHandle &nh, const rosserial_msgs::TopicInfo &topic_info)
Definition: topic_handlers.h:48
rosserial_server::MsgInfo::md5sum
std::string md5sum
Definition: msg_lookup.h:38
ros::serialization::OStream
rosserial_server::ServiceClient::request_message_
topic_tools::ShapeShifter request_message_
Definition: topic_handlers.h:181
ros::Publisher
ros::ServiceClientOptions::persistent
bool persistent
rosserial_server::ServiceClient::setTopicId
void setTopicId(uint16_t topic_id)
Definition: topic_handlers.h:150
ros::serialization::Serializer::write
static void write(Stream &stream, typename boost::call_traits< T >::param_type t)
topic_tools::ShapeShifter::advertise
ros::Publisher advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size_, bool latch=false, const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const
boost::shared_ptr
rosserial_server::ServiceClient::handle
void handle(ros::serialization::IStream stream)
Definition: topic_handlers.h:163
rosserial_server::ServiceClientPtr
boost::shared_ptr< ServiceClient > ServiceClientPtr
Definition: topic_handlers.h:191
rosserial_server::Publisher::get_topic
std::string get_topic()
Definition: topic_handlers.h:74
ros.h
ros::Subscriber::getTopic
std::string getTopic() const
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::serialization::serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
rosserial_server::SubscriberPtr
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: topic_handlers.h:118
rosserial_server::MsgInfo
Definition: msg_lookup.h:36
rosserial_server::Subscriber::Subscriber
Subscriber(ros::NodeHandle &nh, rosserial_msgs::TopicInfo &topic_info, boost::function< void(std::vector< uint8_t > &buffer)> write_fn)
Definition: topic_handlers.h:88
rosserial_server::ServiceClient
Definition: topic_handlers.h:120
ros::serialization::IStream
rosserial_server::ServiceClient::getResponseMessageMD5
std::string getResponseMessageMD5()
Definition: topic_handlers.h:159
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::SubscribeOptions::init
void init(const std::string &_topic, uint32_t _queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &_callback, const boost::function< boost::shared_ptr< M >(void)> &factory_fn=DefaultMessageCreator< M >())
rosserial_server::Publisher
Definition: topic_handlers.h:46
rosserial_server::ServiceClient::service_md5_
std::string service_md5_
Definition: topic_handlers.h:185
ros::SubscribeOptions::md5sum
std::string md5sum
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
rosserial_server::ServiceClient::topic_id_
uint16_t topic_id_
Definition: topic_handlers.h:188
rosserial_server::Publisher::message_
topic_tools::ShapeShifter message_
Definition: topic_handlers.h:80
rosserial_server::Publisher::publisher_
ros::Publisher publisher_
Definition: topic_handlers.h:79
ros::ServiceClientOptions
rosserial_server::Subscriber
Definition: topic_handlers.h:86
rosserial_server::PublisherPtr
boost::shared_ptr< Publisher > PublisherPtr
Definition: topic_handlers.h:83
rosserial_server::Subscriber::subscriber_
ros::Subscriber subscriber_
Definition: topic_handlers.h:114
msg_lookup.h
ros::ServiceClient
rosserial_server::Subscriber::handle
void handle(const boost::shared_ptr< topic_tools::ShapeShifter const > &msg)
Definition: topic_handlers.h:104
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
topic_tools::ShapeShifter::morph
void morph(const std::string &md5sum, const std::string &datatype, const std::string &msg_def, const std::string &latching)
rosserial_server::Publisher::handle
void handle(ros::serialization::IStream stream)
Definition: topic_handlers.h:69
ros::serialization::Serializer::read
static void read(Stream &stream, typename boost::call_traits< T >::reference t)
rosserial_server::ServiceClient::getServiceMD5
std::string getServiceMD5()
Definition: topic_handlers.h:153
shape_shifter.h
ros::ServiceClientOptions::md5sum
std::string md5sum
rosserial_server::lookupMessage
const MsgInfo lookupMessage(const std::string &message_type, const std::string submodule="msg")
Definition: msg_lookup.cpp:36
ros::Publisher::getTopic
std::string getTopic() const
ros::SubscribeOptions
rosserial_server::MsgInfo::full_text
std::string full_text
Definition: msg_lookup.h:39
rosserial_server::ServiceClient::service_client_
ros::ServiceClient service_client_
Definition: topic_handlers.h:183
rosserial_server::ServiceClient::write_fn_
boost::function< void(std::vector< uint8_t > &buffer, const uint16_t topic_id)> write_fn_
Definition: topic_handlers.h:184
rosserial_server::Subscriber::get_topic
std::string get_topic()
Definition: topic_handlers.h:99
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::SubscribeOptions::datatype
std::string datatype
rosserial_server::ServiceClient::ServiceClient
ServiceClient(ros::NodeHandle &nh, rosserial_msgs::TopicInfo &topic_info, boost::function< void(std::vector< uint8_t > &buffer, const uint16_t topic_id)> write_fn)
Definition: topic_handlers.h:122
rosserial_server::ServiceClient::request_message_md5_
std::string request_message_md5_
Definition: topic_handlers.h:186
topic_tools::ShapeShifter
rosserial_server::ServiceClient::response_message_md5_
std::string response_message_md5_
Definition: topic_handlers.h:187
rosserial_server::ServiceClient::getRequestMessageMD5
std::string getRequestMessageMD5()
Definition: topic_handlers.h:156
rosserial_server
Definition: async_read_buffer.h:48
rosserial_server::Subscriber::write_fn_
boost::function< void(std::vector< uint8_t > &buffer)> write_fn_
Definition: topic_handlers.h:115
ros::ServiceClientOptions::service
std::string service
rosserial_server::ServiceClient::response_message_
topic_tools::ShapeShifter response_message_
Definition: topic_handlers.h:182
ros::NodeHandle
ros::Subscriber


rosserial_server
Author(s): Mike Purvis
autogenerated on Wed Mar 2 2022 00:58:14