session.h
Go to the documentation of this file.
1 
35 #ifndef ROSSERIAL_SERVER_SESSION_H
36 #define ROSSERIAL_SERVER_SESSION_H
37 
38 #include <map>
39 #include <boost/bind.hpp>
40 #include <boost/asio.hpp>
41 #include <boost/function.hpp>
42 
43 #include <ros/callback_queue.h>
44 #include <ros/ros.h>
45 #include <rosserial_msgs/TopicInfo.h>
46 #include <rosserial_msgs/Log.h>
48 #include <std_msgs/Time.h>
49 
52 
53 namespace rosserial_server
54 {
55 
56 typedef std::vector<uint8_t> Buffer;
58 
59 template<typename Socket>
60 class Session : boost::noncopyable
61 {
62 public:
63  Session(boost::asio::io_service& io_service)
64  : io_service_(io_service),
65  socket_(io_service),
66  sync_timer_(io_service),
67  require_check_timer_(io_service),
68  ros_spin_timer_(io_service),
70  boost::bind(&Session::read_failed, this,
71  boost::asio::placeholders::error))
72  {
73  active_ = false;
74 
75  timeout_interval_ = boost::posix_time::milliseconds(5000);
76  attempt_interval_ = boost::posix_time::milliseconds(1000);
77  require_check_interval_ = boost::posix_time::milliseconds(1000);
78  ros_spin_interval_ = boost::posix_time::milliseconds(10);
79  require_param_name_ = "~require";
80 
81  unrecognised_topic_retry_threshold_ = ros::param::param("~unrecognised_topic_retry_threshold", 0);
82 
84 
85  // Intermittent callback to service ROS callbacks. To avoid polling like this,
86  // CallbackQueue could in the future be extended with a scheme to monitor for
87  // callbacks on another thread, and then queue them up to be executed on this one.
88  ros_spin_timer_.expires_from_now(ros_spin_interval_);
89  ros_spin_timer_.async_wait(boost::bind(&Session::ros_spin_timeout, this,
90  boost::asio::placeholders::error));
91  }
92 
93  Socket& socket()
94  {
95  return socket_;
96  }
97 
98  void start()
99  {
100  ROS_DEBUG("Starting session.");
101 
102  callbacks_[rosserial_msgs::TopicInfo::ID_PUBLISHER]
103  = boost::bind(&Session::setup_publisher, this, _1);
104  callbacks_[rosserial_msgs::TopicInfo::ID_SUBSCRIBER]
105  = boost::bind(&Session::setup_subscriber, this, _1);
106  callbacks_[rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT+rosserial_msgs::TopicInfo::ID_PUBLISHER]
107  = boost::bind(&Session::setup_service_client_publisher, this, _1);
108  callbacks_[rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT+rosserial_msgs::TopicInfo::ID_SUBSCRIBER]
109  = boost::bind(&Session::setup_service_client_subscriber, this, _1);
110  callbacks_[rosserial_msgs::TopicInfo::ID_LOG]
111  = boost::bind(&Session::handle_log, this, _1);
112  callbacks_[rosserial_msgs::TopicInfo::ID_TIME]
113  = boost::bind(&Session::handle_time, this, _1);
114 
115  active_ = true;
116  attempt_sync();
118  }
119 
120  void stop()
121  {
122  // Abort any pending ROS callbacks.
124 
125  // Abort active session timer callbacks, if present.
126  sync_timer_.cancel();
127  require_check_timer_.cancel();
128 
129  // Reset the state of the session, dropping any publishers or subscribers
130  // we currently know about from this client.
131  callbacks_.clear();
132  subscribers_.clear();
133  publishers_.clear();
134  services_.clear();
135 
136  // Close the socket.
137  socket_.close();
138  active_ = false;
139  }
140 
141  void shutdown()
142  {
143  if (is_active())
144  {
145  stop();
146  }
147  io_service_.stop();
148  }
149 
150  bool is_active()
151  {
152  return active_;
153  }
154 
161  void set_require_param(std::string param_name)
162  {
163  require_param_name_ = param_name;
164  }
165 
166 private:
171  void ros_spin_timeout(const boost::system::error_code& error) {
173 
174  if (ros::ok())
175  {
176  // Call again next interval.
177  ros_spin_timer_.expires_from_now(ros_spin_interval_);
178  ros_spin_timer_.async_wait(boost::bind(&Session::ros_spin_timeout, this,
179  boost::asio::placeholders::error));
180  }
181  else
182  {
183  shutdown();
184  }
185  }
186 
188  // TODO: Total message timeout, implement primarily in ReadBuffer.
189 
191  async_read_buffer_.read(1, boost::bind(&Session::read_sync_first, this, _1));
192  }
193 
195  uint8_t sync;
196  stream >> sync;
197  if (sync == 0xff) {
198  async_read_buffer_.read(1, boost::bind(&Session::read_sync_second, this, _1));
199  } else {
201  }
202  }
203 
205  uint8_t sync;
206  stream >> sync;
207  if (sync == 0xfe) {
208  async_read_buffer_.read(5, boost::bind(&Session::read_id_length, this, _1));
209  } else {
211  }
212  }
213 
215  uint16_t topic_id, length;
216  uint8_t length_checksum;
217 
218  // Check header checksum byte for length field.
219  stream >> length >> length_checksum;
220  if (length_checksum + checksum(length) != 0xff) {
221  uint8_t csl = checksum(length);
222  ROS_WARN("Bad message header length checksum. Dropping message from client. T%d L%d C%d %d", topic_id, length, length_checksum, csl);
224  return;
225  } else {
226  stream >> topic_id;
227  }
228  ROS_DEBUG("Received message header with length %d and topic_id=%d", length, topic_id);
229 
230  // Read message length + checksum byte.
231  async_read_buffer_.read(length + 1, boost::bind(&Session::read_body, this,
232  _1, topic_id));
233  }
234 
235  void read_body(ros::serialization::IStream& stream, uint16_t topic_id) {
236  ROS_DEBUG("Received body of length %d for message on topic %d.", stream.getLength(), topic_id);
237 
238  ros::serialization::IStream checksum_stream(stream.getData(), stream.getLength());
239  uint8_t msg_checksum = checksum(checksum_stream) + checksum(topic_id);
240 
241  if (msg_checksum != 0xff) {
242  ROS_WARN("Rejecting message on topicId=%d, length=%d with bad checksum.", topic_id, stream.getLength());
243  } else {
244  if (callbacks_.count(topic_id) == 1) {
245  try {
246  // stream includes the check sum byte.
247  ros::serialization::IStream msg_stream(stream.getData(), stream.getLength()-1);
248  callbacks_[topic_id](msg_stream);
250  if (topic_id < 100) {
251  ROS_ERROR("Buffer overrun when attempting to parse setup message.");
252  ROS_ERROR_ONCE("Is this firmware from a pre-Groovy rosserial?");
253  } else {
254  ROS_WARN("Buffer overrun when attempting to parse user message.");
255  }
256  }
257  } else {
258  ROS_WARN("Received message with unrecognized topicId (%d).", topic_id);
259 
261  {
262  // The threshold for unrecognised topics has been exceeded.
263  // Attempt to request the topics from the client again
264  ROS_WARN("Unrecognised topic threshold exceeded. Requesting topics from client");
265  attempt_sync();
267  }
268  }
269  }
270 
271  // Kickoff next message read.
273  }
274 
275  void read_failed(const boost::system::error_code& error) {
276  if (error == boost::system::errc::no_buffer_space) {
277  // No worries. Begin syncing on a new message.
278  ROS_WARN("Overrun on receive buffer. Attempting to regain rx sync.");
280  } else if (error) {
281  // When some other read error has occurred, stop the session, which destroys
282  // all known publishers and subscribers.
283  ROS_WARN_STREAM("Socket asio error, closing socket: " << error);
284  stop();
285  }
286  }
287 
289 
290  void write_message(Buffer& message, const uint16_t topic_id) {
291  uint8_t overhead_bytes = 8;
292  uint16_t length = overhead_bytes + message.size();
293  BufferPtr buffer_ptr(new Buffer(length));
294 
295  uint8_t msg_checksum;
296  ros::serialization::IStream checksum_stream(message.size() > 0 ? &message[0] : NULL, message.size());
297 
298  ros::serialization::OStream stream(&buffer_ptr->at(0), buffer_ptr->size());
299  uint8_t msg_len_checksum = 255 - checksum(message.size());
300  stream << (uint16_t)0xfeff << (uint16_t)message.size() << msg_len_checksum << topic_id;
301  msg_checksum = 255 - (checksum(checksum_stream) + checksum(topic_id));
302 
303  memcpy(stream.advance(message.size()), &message[0], message.size());
304  stream << msg_checksum;
305 
306  ROS_DEBUG_NAMED("async_write", "Sending buffer of %d bytes to client.", length);
307  boost::asio::async_write(socket_, boost::asio::buffer(*buffer_ptr),
308  boost::bind(&Session::write_completion_cb, this, boost::asio::placeholders::error, buffer_ptr));
309  }
310 
311  void write_completion_cb(const boost::system::error_code& error,
312  BufferPtr buffer_ptr) {
313  if (error) {
314  if (error == boost::system::errc::io_error) {
315  ROS_WARN_THROTTLE(1, "Socket write operation returned IO error.");
316  } else if (error == boost::system::errc::no_such_device) {
317  ROS_WARN_THROTTLE(1, "Socket write operation returned no device.");
318  } else {
319  ROS_WARN_STREAM_THROTTLE(1, "Unknown error returned during write operation: " << error);
320  }
321  stop();
322  }
323  // Buffer is destructed when this function exits and buffer_ptr goes out of scope.
324  }
325 
327  void attempt_sync() {
328  request_topics();
330  }
331 
332  void set_sync_timeout(const boost::posix_time::time_duration& interval) {
333  if (ros::ok())
334  {
335  sync_timer_.cancel();
336  sync_timer_.expires_from_now(interval);
337  sync_timer_.async_wait(boost::bind(&Session::sync_timeout, this,
338  boost::asio::placeholders::error));
339  }
340  else
341  {
342  shutdown();
343  }
344  }
345 
346  void sync_timeout(const boost::system::error_code& error) {
347  if (error != boost::asio::error::operation_aborted) {
348  ROS_DEBUG("Sync with device lost.");
349  stop();
350  }
351  }
352 
354  void request_topics() {
355  std::vector<uint8_t> message(0);
356  ROS_DEBUG("Sending request topics message for VER2 protocol.");
357  write_message(message, rosserial_msgs::TopicInfo::ID_PUBLISHER);
358 
359  // Set timer for future point at which to verify the subscribers and publishers
360  // created by the client against the expected set given in the parameters.
362  require_check_timer_.async_wait(boost::bind(&Session::required_topics_check, this,
363  boost::asio::placeholders::error));
364  }
365 
366  void required_topics_check(const boost::system::error_code& error) {
367  if (error != boost::asio::error::operation_aborted) {
369  if (!check_set(require_param_name_ + "/publishers", publishers_) ||
370  !check_set(require_param_name_ + "/subscribers", subscribers_)) {
371  ROS_WARN("Connected client failed to establish the publishers and subscribers dictated by require parameter. Re-requesting topics.");
372  request_topics();
373  }
374  }
375  }
376  }
377 
378  template<typename M>
379  bool check_set(std::string param_name, M map) {
380  XmlRpc::XmlRpcValue param_list;
381  ros::param::get(param_name, param_list);
383  for (int i = 0; i < param_list.size(); ++i) {
384  ROS_ASSERT(param_list[i].getType() == XmlRpc::XmlRpcValue::TypeString);
385  std::string required_topic((std::string(param_list[i])));
386  // Iterate through map of registered topics, to ensure that this one is present.
387  bool found = false;
388  for (typename M::iterator j = map.begin(); j != map.end(); ++j) {
389  if (nh_.resolveName(j->second->get_topic()) ==
390  nh_.resolveName(required_topic)) {
391  found = true;
392  ROS_INFO_STREAM("Verified connection to topic " << required_topic << ", given in parameter " << param_name);
393  break;
394  }
395  }
396  if (!found) {
397  ROS_WARN_STREAM("Missing connection to topic " << required_topic << ", required by parameter " << param_name);
398  return false;
399  }
400  }
401  return true;
402  }
403 
404  static uint8_t checksum(ros::serialization::IStream& stream) {
405  uint8_t sum = 0;
406  for (uint16_t i = 0; i < stream.getLength(); ++i) {
407  sum += stream.getData()[i];
408  }
409  return sum;
410  }
411 
412  static uint8_t checksum(uint16_t val) {
413  return (val >> 8) + val;
414  }
415 
417 
419  rosserial_msgs::TopicInfo topic_info;
421 
422  PublisherPtr pub(new Publisher(nh_, topic_info));
423  callbacks_[topic_info.topic_id] = boost::bind(&Publisher::handle, pub, _1);
424  publishers_[topic_info.topic_id] = pub;
425 
427  }
428 
430  rosserial_msgs::TopicInfo topic_info;
432 
433  SubscriberPtr sub(new Subscriber(nh_, topic_info,
434  boost::bind(&Session::write_message, this, _1, topic_info.topic_id)));
435  subscribers_[topic_info.topic_id] = sub;
436 
438  }
439 
440  // When the rosserial client creates a ServiceClient object (and/or when it registers that object with the NodeHandle)
441  // it creates a publisher (to publish the service request message to us) and a subscriber (to receive the response)
442  // the service client callback is attached to the *subscriber*, so when we receive the service response
443  // and wish to send it over the socket to the client,
444  // we must attach the topicId that came from the service client subscriber message
445 
447  rosserial_msgs::TopicInfo topic_info;
449 
450  if (!services_.count(topic_info.topic_name)) {
451  ROS_DEBUG("Creating service client for topic %s",topic_info.topic_name.c_str());
453  nh_,topic_info,boost::bind(&Session::write_message, this, _1, _2)));
454  services_[topic_info.topic_name] = srv;
455  callbacks_[topic_info.topic_id] = boost::bind(&ServiceClient::handle, srv, _1);
456  }
457  if (services_[topic_info.topic_name]->getRequestMessageMD5() != topic_info.md5sum) {
458  ROS_WARN("Service client setup: Request message MD5 mismatch between rosserial client and ROS");
459  } else {
460  ROS_DEBUG("Service client %s: request message MD5 successfully validated as %s",
461  topic_info.topic_name.c_str(),topic_info.md5sum.c_str());
462  }
464  }
465 
467  rosserial_msgs::TopicInfo topic_info;
469 
470  if (!services_.count(topic_info.topic_name)) {
471  ROS_DEBUG("Creating service client for topic %s",topic_info.topic_name.c_str());
473  nh_,topic_info,boost::bind(&Session::write_message, this, _1, _2)));
474  services_[topic_info.topic_name] = srv;
475  callbacks_[topic_info.topic_id] = boost::bind(&ServiceClient::handle, srv, _1);
476  }
477  // see above comment regarding the service client callback for why we set topic_id here
478  services_[topic_info.topic_name]->setTopicId(topic_info.topic_id);
479  if (services_[topic_info.topic_name]->getResponseMessageMD5() != topic_info.md5sum) {
480  ROS_WARN("Service client setup: Response message MD5 mismatch between rosserial client and ROS");
481  } else {
482  ROS_DEBUG("Service client %s: response message MD5 successfully validated as %s",
483  topic_info.topic_name.c_str(),topic_info.md5sum.c_str());
484  }
486  }
487 
489  rosserial_msgs::Log l;
491  if(l.level == rosserial_msgs::Log::ROSDEBUG) ROS_DEBUG("%s", l.msg.c_str());
492  else if(l.level == rosserial_msgs::Log::INFO) ROS_INFO("%s", l.msg.c_str());
493  else if(l.level == rosserial_msgs::Log::WARN) ROS_WARN("%s", l.msg.c_str());
494  else if(l.level == rosserial_msgs::Log::ERROR) ROS_ERROR("%s", l.msg.c_str());
495  else if(l.level == rosserial_msgs::Log::FATAL) ROS_FATAL("%s", l.msg.c_str());
496  }
497 
499  std_msgs::Time time;
500  time.data = ros::Time::now();
501 
502  size_t length = ros::serialization::serializationLength(time);
503  std::vector<uint8_t> message(length);
504 
505  ros::serialization::OStream ostream(&message[0], length);
507 
508  write_message(message, rosserial_msgs::TopicInfo::ID_TIME);
509 
510  // The MCU requesting the time from the server is the sync notification. This
511  // call moves the timeout forward.
513  }
514 
515  boost::asio::io_service& io_service_;
516  Socket socket_;
518  enum { buffer_max = 1023 };
519  bool active_;
520 
523 
524  boost::posix_time::time_duration timeout_interval_;
525  boost::posix_time::time_duration attempt_interval_;
526  boost::posix_time::time_duration require_check_interval_;
527  boost::posix_time::time_duration ros_spin_interval_;
528  boost::asio::deadline_timer sync_timer_;
529  boost::asio::deadline_timer require_check_timer_;
530  boost::asio::deadline_timer ros_spin_timer_;
531  std::string require_param_name_;
534 
535  std::map<uint16_t, boost::function<void(ros::serialization::IStream&)> > callbacks_;
536  std::map<uint16_t, PublisherPtr> publishers_;
537  std::map<uint16_t, SubscriberPtr> subscribers_;
538  std::map<std::string, ServiceClientPtr> services_;
539 };
540 
541 } // namespace
542 
543 #endif // ROSSERIAL_SERVER_SESSION_H
XmlRpc::XmlRpcValue::size
int size() const
ros::serialization::OStream
rosserial_server::Session::setup_service_client_publisher
void setup_service_client_publisher(ros::serialization::IStream &stream)
Definition: session.h:446
rosserial_server::Session::active_
bool active_
Definition: session.h:519
rosserial_server::Session::Session
Session(boost::asio::io_service &io_service)
Definition: session.h:63
rosserial_server::Session::buffer_max
@ buffer_max
Definition: session.h:518
rosserial_server::Session::set_sync_timeout
void set_sync_timeout(const boost::posix_time::time_duration &interval)
Definition: session.h:332
ROS_ERROR_ONCE
#define ROS_ERROR_ONCE(...)
ros::serialization::Serializer::write
static void write(Stream &stream, typename boost::call_traits< T >::param_type t)
boost::shared_ptr
rosserial_server::ServiceClient::handle
void handle(ros::serialization::IStream stream)
Definition: topic_handlers.h:163
rosserial_server::Session::async_read_buffer_
AsyncReadBuffer< Socket > async_read_buffer_
Definition: session.h:517
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
ros.h
ros::CallbackQueue::clear
void clear()
rosserial_server::Session::handle_time
void handle_time(ros::serialization::IStream &stream)
Definition: session.h:498
ros::serialization::serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
rosserial_server::Session::check_set
bool check_set(std::string param_name, M map)
Definition: session.h:379
rosserial_server::Session::write_completion_cb
void write_completion_cb(const boost::system::error_code &error, BufferPtr buffer_ptr)
Definition: session.h:311
boost
rosserial_server::ServiceClient
Definition: topic_handlers.h:120
rosserial_server::Session::setup_subscriber
void setup_subscriber(ros::serialization::IStream &stream)
Definition: session.h:429
ros::serialization::Stream::advance
ROS_FORCE_INLINE uint8_t * advance(uint32_t len)
ros::serialization::IStream
rosserial_server::Session::read_body
void read_body(ros::serialization::IStream &stream, uint16_t topic_id)
Definition: session.h:235
rosserial_server::Session::require_param_name_
std::string require_param_name_
Definition: session.h:531
rosserial_server::Session::ros_spin_timer_
boost::asio::deadline_timer ros_spin_timer_
Definition: session.h:530
rosserial_server::Session
Definition: session.h:60
ros::ok
ROSCPP_DECL bool ok()
rosserial_server::Session::timeout_interval_
boost::posix_time::time_duration timeout_interval_
Definition: session.h:524
rosserial_server::Session::unrecognised_topics_
int unrecognised_topics_
Definition: session.h:533
rosserial_server::Session::read_sync_header
void read_sync_header()
Definition: session.h:190
rosserial_server::Session::io_service_
boost::asio::io_service & io_service_
Definition: session.h:515
rosserial_server::Session::read_sync_second
void read_sync_second(ros::serialization::IStream &stream)
Definition: session.h:204
topic_handlers.h
Classes which manage the Publish and Subscribe relationships that a Session has with its client.
rosserial_server::Publisher
Definition: topic_handlers.h:46
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
rosserial_server::Session::read_id_length
void read_id_length(ros::serialization::IStream &stream)
Definition: session.h:214
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
rosserial_server::Session::require_check_interval_
boost::posix_time::time_duration require_check_interval_
Definition: session.h:526
rosserial_server::Session::publishers_
std::map< uint16_t, PublisherPtr > publishers_
Definition: session.h:536
ros::CallbackQueue
ROS_DEBUG
#define ROS_DEBUG(...)
rosserial_server::AsyncReadBuffer< Socket >
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
XmlRpc::XmlRpcValue::TypeString
TypeString
rosserial_server::Subscriber
Definition: topic_handlers.h:86
rosserial_server::AsyncReadBuffer::read
void read(size_t requested_bytes, boost::function< void(ros::serialization::IStream &)> callback)
Commands a fixed number of bytes from the buffer. This may be fulfilled from existing buffer content,...
Definition: async_read_buffer.h:67
rosserial_server::Buffer
std::vector< uint8_t > Buffer
Definition: session.h:56
rosserial_server::Session::read_failed
void read_failed(const boost::system::error_code &error)
Definition: session.h:275
ROS_WARN
#define ROS_WARN(...)
rosserial_server::Session::unrecognised_topic_retry_threshold_
int unrecognised_topic_retry_threshold_
Definition: session.h:532
rosserial_server::Session::require_check_timer_
boost::asio::deadline_timer require_check_timer_
Definition: session.h:529
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rosserial_server::Publisher::handle
void handle(ros::serialization::IStream stream)
Definition: topic_handlers.h:69
rosserial_server::Session::stop
void stop()
Definition: session.h:120
rosserial_server::Session::shutdown
void shutdown()
Definition: session.h:141
rosserial_server::Session::ros_spin_interval_
boost::posix_time::time_duration ros_spin_interval_
Definition: session.h:527
rosserial_server::Session::services_
std::map< std::string, ServiceClientPtr > services_
Definition: session.h:538
XmlRpc::XmlRpcValue::getType
const Type & getType() const
rosserial_server::Session::checksum
static uint8_t checksum(ros::serialization::IStream &stream)
Definition: session.h:404
ROS_FATAL
#define ROS_FATAL(...)
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
rosserial_server::Session::ros_callback_queue_
ros::CallbackQueue ros_callback_queue_
Definition: session.h:522
rosserial_server::Session::socket
Socket & socket()
Definition: session.h:93
ros::serialization::Serializer::read
static void read(Stream &stream, typename boost::call_traits< T >::reference t)
callback_queue.h
rosserial_server::Session::sync_timer_
boost::asio::deadline_timer sync_timer_
Definition: session.h:528
XmlRpc::XmlRpcValue::TypeArray
TypeArray
rosserial_server::Session::subscribers_
std::map< uint16_t, SubscriberPtr > subscribers_
Definition: session.h:537
rosserial_server::Session::handle_log
void handle_log(ros::serialization::IStream &stream)
Definition: session.h:488
shape_shifter.h
ros::serialization::StreamOverrunException
rosserial_server::Session::callbacks_
std::map< uint16_t, boost::function< void(ros::serialization::IStream &)> > callbacks_
Definition: session.h:535
rosserial_server::BufferPtr
boost::shared_ptr< Buffer > BufferPtr
Definition: session.h:57
ros::serialization::Stream::getLength
uint32_t getLength()
rosserial_server::Session::write_message
void write_message(Buffer &message, const uint16_t topic_id)
Definition: session.h:290
async_read_buffer.h
Helper object for successive reads from a ReadStream.
rosserial_server::Session::setup_publisher
void setup_publisher(ros::serialization::IStream &stream)
Definition: session.h:418
rosserial_server::Session::start
void start()
Definition: session.h:98
ROS_ERROR
#define ROS_ERROR(...)
ros::serialization::Stream::getData
uint8_t * getData()
ros::param::param
T param(const std::string &param_name, const T &default_val)
rosserial_server::Session::setup_service_client_subscriber
void setup_service_client_subscriber(ros::serialization::IStream &stream)
Definition: session.h:466
rosserial_server::Session::sync_timeout
void sync_timeout(const boost::system::error_code &error)
Definition: session.h:346
rosserial_server::Session::required_topics_check
void required_topics_check(const boost::system::error_code &error)
Definition: session.h:366
rosserial_server::Session::attempt_interval_
boost::posix_time::time_duration attempt_interval_
Definition: session.h:525
ros::param::has
ROSCPP_DECL bool has(const std::string &key)
rosserial_server::Session::read_sync_first
void read_sync_first(ros::serialization::IStream &stream)
Definition: session.h:194
rosserial_server::Session::attempt_sync
void attempt_sync()
Definition: session.h:327
rosserial_server::Session::nh_
ros::NodeHandle nh_
Definition: session.h:521
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
rosserial_server::Session::checksum
static uint8_t checksum(uint16_t val)
Definition: session.h:412
rosserial_server
Definition: async_read_buffer.h:48
ros::CallbackQueue::callAvailable
void callAvailable()
rosserial_server::Session::is_active
bool is_active()
Definition: session.h:150
XmlRpc::XmlRpcValue
rosserial_server::Session::ros_spin_timeout
void ros_spin_timeout(const boost::system::error_code &error)
Definition: session.h:171
ros::NodeHandle
rosserial_server::Session::request_topics
void request_topics()
Definition: session.h:354
rosserial_server::Session::set_require_param
void set_require_param(std::string param_name)
Definition: session.h:161
ros::Time::now
static Time now()
rosserial_server::Session::socket_
Socket socket_
Definition: session.h:516


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