node_handle.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote prducts derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef ROS_NODE_HANDLE_H_
36 #define ROS_NODE_HANDLE_H_
37 
38 #include <stdint.h>
39 
40 #include "std_msgs/Time.h"
41 #include "rosserial_msgs/TopicInfo.h"
42 #include "rosserial_msgs/Log.h"
43 #include "rosserial_msgs/RequestParam.h"
44 
45 #include "ros/msg.h"
46 
47 namespace ros
48 {
49 
51 {
52 public:
53  virtual int publish(int id, const Msg* msg) = 0;
54  virtual int spinOnce() = 0;
55  virtual bool connected() = 0;
56 };
57 }
58 
59 #include "ros/publisher.h"
60 #include "ros/subscriber.h"
61 #include "ros/service_server.h"
62 #include "ros/service_client.h"
63 
64 namespace ros
65 {
66 
67 const int SPIN_OK = 0;
68 const int SPIN_ERR = -1;
69 const int SPIN_TIMEOUT = -2;
70 const int SPIN_TX_STOP_REQUESTED = -3;
71 const int SPIN_TIME_RECV = -4;
72 
73 const uint8_t SYNC_SECONDS = 5;
74 const uint8_t MODE_FIRST_FF = 0;
75 /*
76  * The second sync byte is a protocol version. It's value is 0xff for the first
77  * version of the rosserial protocol (used up to hydro), 0xfe for the second version
78  * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable
79  * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy
80  * rosserial_arduino. It must be changed in both this file and in
81  * rosserial_python/src/rosserial_python/SerialClient.py
82  */
83 const uint8_t MODE_PROTOCOL_VER = 1;
84 const uint8_t PROTOCOL_VER1 = 0xff; // through groovy
85 const uint8_t PROTOCOL_VER2 = 0xfe; // in hydro
86 const uint8_t PROTOCOL_VER = PROTOCOL_VER2;
87 const uint8_t MODE_SIZE_L = 2;
88 const uint8_t MODE_SIZE_H = 3;
89 const uint8_t MODE_SIZE_CHECKSUM = 4; // checksum for msg size received from size L and H
90 const uint8_t MODE_TOPIC_L = 5; // waiting for topic id
91 const uint8_t MODE_TOPIC_H = 6;
92 const uint8_t MODE_MESSAGE = 7;
93 const uint8_t MODE_MSG_CHECKSUM = 8; // checksum for msg and topic id
94 
95 
96 const uint8_t SERIAL_MSG_TIMEOUT = 20; // 20 milliseconds to recieve all of message data
97 
98 using rosserial_msgs::TopicInfo;
99 
100 /* Node Handle */
101 template<class Hardware,
102  int MAX_SUBSCRIBERS = 25,
103  int MAX_PUBLISHERS = 25,
104  int INPUT_SIZE = 512,
105  int OUTPUT_SIZE = 512>
107 {
108 protected:
109  Hardware hardware_{};
110 
111  /* time used for syncing */
112  uint32_t rt_time{0};
113 
114  /* used for computing current time */
115  uint32_t sec_offset{0}, nsec_offset{0};
116 
117  /* Spinonce maximum work timeout */
118  uint32_t spin_timeout_{0};
119 
120  uint8_t message_in[INPUT_SIZE] = {0};
121  uint8_t message_out[OUTPUT_SIZE] = {0};
122 
123  Publisher * publishers[MAX_PUBLISHERS] = {nullptr};
124  Subscriber_ * subscribers[MAX_SUBSCRIBERS] {nullptr};
125 
126  /*
127  * Setup Functions
128  */
129 public:
130  Hardware* getHardware()
131  {
132  return &hardware_;
133  }
134 
135  /* Start serial, initialize buffers */
136  void initNode()
137  {
138  hardware_.init();
139  mode_ = 0;
140  bytes_ = 0;
141  index_ = 0;
142  topic_ = 0;
143  };
144 
145  /* Start a named port, which may be network server IP, initialize buffers */
146  void initNode(char *portName)
147  {
148  hardware_.init(portName);
149  mode_ = 0;
150  bytes_ = 0;
151  index_ = 0;
152  topic_ = 0;
153  };
154 
163  void setSpinTimeout(const uint32_t& timeout)
164  {
165  spin_timeout_ = timeout;
166  }
167 
168 protected:
169  // State machine variables for spinOnce
170  int mode_{0};
171  int bytes_{0};
172  int topic_{0};
173  int index_{0};
174  int checksum_{0};
175 
176  bool configured_{false};
177 
178  /* used for syncing the time */
179  uint32_t last_sync_time{0};
182 
183 public:
184  /* This function goes in your loop() function, it handles
185  * serial input and callbacks for subscribers.
186  */
187 
188 
189  virtual int spinOnce() override
190  {
191  /* restart if timed out */
192  uint32_t c_time = hardware_.time();
193  if ((c_time - last_sync_receive_time) > (SYNC_SECONDS * 2200))
194  {
195  configured_ = false;
196  }
197 
198  /* reset if message has timed out */
199  if (mode_ != MODE_FIRST_FF)
200  {
201  if (c_time > last_msg_timeout_time)
202  {
204  }
205  }
206 
207  bool tx_stop_requested = false;
208  bool saw_time_msg = false;
209 
210  /* while available buffer, read data */
211  while (true)
212  {
213  // If a timeout has been specified, check how long spinOnce has been running.
214  if (spin_timeout_ > 0)
215  {
216  // If the maximum processing timeout has been exceeded, exit with error.
217  // The next spinOnce can continue where it left off, or optionally
218  // based on the application in use, the hardware buffer could be flushed
219  // and start fresh.
220  if ((hardware_.time() - c_time) > spin_timeout_)
221  {
222  // Exit the spin, processing timeout exceeded.
223  return SPIN_TIMEOUT;
224  }
225  }
226  int data = hardware_.read();
227  if (data < 0)
228  break;
229  checksum_ += data;
230  if (mode_ == MODE_MESSAGE) /* message data being recieved */
231  {
232  message_in[index_++] = data;
233  bytes_--;
234  if (bytes_ == 0) /* is message complete? if so, checksum */
236  }
237  else if (mode_ == MODE_FIRST_FF)
238  {
239  if (data == 0xff)
240  {
241  mode_++;
243  }
244  else if (hardware_.time() - c_time > (SYNC_SECONDS * 1000))
245  {
246  /* We have been stuck in spinOnce too long, return error */
247  configured_ = false;
248  return SPIN_TIMEOUT;
249  }
250  }
251  else if (mode_ == MODE_PROTOCOL_VER)
252  {
253  if (data == PROTOCOL_VER)
254  {
255  mode_++;
256  }
257  else
258  {
260  if (configured_ == false)
261  requestSyncTime(); /* send a msg back showing our protocol version */
262  }
263  }
264  else if (mode_ == MODE_SIZE_L) /* bottom half of message size */
265  {
266  bytes_ = data;
267  index_ = 0;
268  mode_++;
269  checksum_ = data; /* first byte for calculating size checksum */
270  }
271  else if (mode_ == MODE_SIZE_H) /* top half of message size */
272  {
273  bytes_ += data << 8;
274  mode_++;
275  }
276  else if (mode_ == MODE_SIZE_CHECKSUM)
277  {
278  if ((checksum_ % 256) == 255)
279  mode_++;
280  else
281  mode_ = MODE_FIRST_FF; /* Abandon the frame if the msg len is wrong */
282  }
283  else if (mode_ == MODE_TOPIC_L) /* bottom half of topic id */
284  {
285  topic_ = data;
286  mode_++;
287  checksum_ = data; /* first byte included in checksum */
288  }
289  else if (mode_ == MODE_TOPIC_H) /* top half of topic id */
290  {
291  topic_ += data << 8;
293  if (bytes_ == 0)
295  }
296  else if (mode_ == MODE_MSG_CHECKSUM) /* do checksum */
297  {
299  if ((checksum_ % 256) == 255)
300  {
301  if (topic_ == TopicInfo::ID_PUBLISHER)
302  {
303  requestSyncTime();
304  negotiateTopics();
305  last_sync_time = c_time;
306  last_sync_receive_time = c_time;
307  return SPIN_ERR;
308  }
309  else if (topic_ == TopicInfo::ID_TIME)
310  {
311  saw_time_msg = true;
313  }
314  else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST)
315  {
316  req_param_resp.deserialize(message_in);
317  param_received = true;
318  }
319  else if (topic_ == TopicInfo::ID_TX_STOP)
320  {
321  configured_ = false;
322  tx_stop_requested = true;
323  }
324  else
325  {
326  if (subscribers[topic_ - 100])
328  }
329  }
330  }
331  }
332 
333  /* occasionally sync time */
334  if (configured_ && ((c_time - last_sync_time) > (SYNC_SECONDS * 500)))
335  {
336  requestSyncTime();
337  last_sync_time = c_time;
338  }
339 
340  return saw_time_msg ? SPIN_TIME_RECV : (tx_stop_requested ? SPIN_TX_STOP_REQUESTED : SPIN_OK);
341  }
342 
343 
344  /* Are we connected to the PC? */
345  virtual bool connected() override
346  {
347  return configured_;
348  };
349 
350  /********************************************************************
351  * Time functions
352  */
353 
355  {
356  std_msgs::Time t;
357  publish(TopicInfo::ID_TIME, &t);
358  rt_time = hardware_.time();
359  }
360 
361  void syncTime(uint8_t * data)
362  {
363  std_msgs::Time t;
364  uint32_t offset = hardware_.time() - rt_time;
365 
366  t.deserialize(data);
367  t.data.sec += offset / 1000;
368  t.data.nsec += (offset % 1000) * 1000000UL;
369 
370  this->setNow(t.data);
372  }
373 
375  {
376  uint32_t ms = hardware_.time();
377  Time current_time;
378  current_time.sec = ms / 1000 + sec_offset;
379  current_time.nsec = (ms % 1000) * 1000000UL + nsec_offset;
380  normalizeSecNSec(current_time.sec, current_time.nsec);
381  return current_time;
382  }
383 
384  void setNow(const Time & new_now)
385  {
386  uint32_t ms = hardware_.time();
387  sec_offset = new_now.sec - ms / 1000 - 1;
388  nsec_offset = new_now.nsec - (ms % 1000) * 1000000UL + 1000000000UL;
390  }
391 
392  /********************************************************************
393  * Topic Management
394  */
395 
396  /* Register a new publisher */
398  {
399  for (int i = 0; i < MAX_PUBLISHERS; i++)
400  {
401  if (publishers[i] == 0) // empty slot
402  {
403  publishers[i] = &p;
404  p.id_ = i + 100 + MAX_SUBSCRIBERS;
405  p.nh_ = this;
406  return true;
407  }
408  }
409  return false;
410  }
411 
412  /* Register a new subscriber */
414  {
415  for (int i = 0; i < MAX_SUBSCRIBERS; i++)
416  {
417  if (subscribers[i] == 0) // empty slot
418  {
419  subscribers[i] = &s;
420  s.id_ = i + 100;
421  return true;
422  }
423  }
424  return false;
425  }
426 
427  /* Register a new Service Server */
428  template<typename MReq, typename MRes, typename ObjT>
430  {
431  bool v = advertise(srv.pub);
432  bool w = subscribe(srv);
433  return v && w;
434  }
435 
436  /* Register a new Service Client */
437  template<typename MReq, typename MRes>
439  {
440  bool v = advertise(srv.pub);
441  bool w = subscribe(srv);
442  return v && w;
443  }
444 
446  {
447  rosserial_msgs::TopicInfo ti;
448  int i;
449  for (i = 0; i < MAX_PUBLISHERS; i++)
450  {
451  if (publishers[i] != 0) // non-empty slot
452  {
453  ti.topic_id = publishers[i]->id_;
454  ti.topic_name = (char *) publishers[i]->topic_;
455  ti.message_type = (char *) publishers[i]->msg_->getType();
456  ti.md5sum = (char *) publishers[i]->msg_->getMD5();
457  ti.buffer_size = OUTPUT_SIZE;
458  publish(publishers[i]->getEndpointType(), &ti);
459  }
460  }
461  for (i = 0; i < MAX_SUBSCRIBERS; i++)
462  {
463  if (subscribers[i] != 0) // non-empty slot
464  {
465  ti.topic_id = subscribers[i]->id_;
466  ti.topic_name = (char *) subscribers[i]->topic_;
467  ti.message_type = (char *) subscribers[i]->getMsgType();
468  ti.md5sum = (char *) subscribers[i]->getMsgMD5();
469  ti.buffer_size = INPUT_SIZE;
470  publish(subscribers[i]->getEndpointType(), &ti);
471  }
472  }
473  configured_ = true;
474  }
475 
476  virtual int publish(int id, const Msg * msg) override
477  {
478  if (id >= 100 && !configured_)
479  return 0;
480 
481  /* serialize message */
482  int l = msg->serialize(message_out + 7);
483 
484  /* setup the header */
485  message_out[0] = 0xff;
487  message_out[2] = (uint8_t)((uint16_t)l & 255);
488  message_out[3] = (uint8_t)((uint16_t)l >> 8);
489  message_out[4] = 255 - ((message_out[2] + message_out[3]) % 256);
490  message_out[5] = (uint8_t)((int16_t)id & 255);
491  message_out[6] = (uint8_t)((int16_t)id >> 8);
492 
493  /* calculate checksum */
494  int chk = 0;
495  for (int i = 5; i < l + 7; i++)
496  chk += message_out[i];
497  l += 7;
498  message_out[l++] = 255 - (chk % 256);
499 
500  if (l <= OUTPUT_SIZE)
501  {
502  hardware_.write(message_out, l);
503  return l;
504  }
505  else
506  {
507  logerror("Message from device dropped: message larger than buffer.");
508  return -1;
509  }
510  }
511 
512  /********************************************************************
513  * Logging
514  */
515 
516 protected:
517  void log(char byte, const char * msg)
518  {
519  rosserial_msgs::Log l;
520  l.level = byte;
521  l.msg = (char*)msg;
522  publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
523  }
524 
525 public:
526  void logdebug(const char* msg)
527  {
528  log(rosserial_msgs::Log::ROSDEBUG, msg);
529  }
530  void loginfo(const char * msg)
531  {
532  log(rosserial_msgs::Log::INFO, msg);
533  }
534  void logwarn(const char *msg)
535  {
536  log(rosserial_msgs::Log::WARN, msg);
537  }
538  void logerror(const char*msg)
539  {
540  log(rosserial_msgs::Log::ERROR, msg);
541  }
542  void logfatal(const char*msg)
543  {
544  log(rosserial_msgs::Log::FATAL, msg);
545  }
546 
547  /********************************************************************
548  * Parameters
549  */
550 
551 protected:
552  bool param_received{false};
553  rosserial_msgs::RequestParamResponse req_param_resp{};
554 
555  bool requestParam(const char * name, int time_out = 1000)
556  {
557  param_received = false;
558  rosserial_msgs::RequestParamRequest req;
559  req.name = (char*)name;
560  publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
561  uint32_t end_time = hardware_.time() + time_out;
562  while (!param_received)
563  {
564  spinOnce();
565  if (hardware_.time() > end_time)
566  {
567  logwarn("Failed to get param: timeout expired");
568  return false;
569  }
570  }
571  return true;
572  }
573 
574 public:
575  bool getParam(const char* name, int* param, int length = 1, int timeout = 1000)
576  {
577  if (requestParam(name, timeout))
578  {
579  if (length == req_param_resp.ints_length)
580  {
581  //copy it over
582  for (int i = 0; i < length; i++)
583  param[i] = req_param_resp.ints[i];
584  return true;
585  }
586  else
587  {
588  logwarn("Failed to get param: length mismatch");
589  }
590  }
591  return false;
592  }
593  bool getParam(const char* name, float* param, int length = 1, int timeout = 1000)
594  {
595  if (requestParam(name, timeout))
596  {
597  if (length == req_param_resp.floats_length)
598  {
599  //copy it over
600  for (int i = 0; i < length; i++)
601  param[i] = req_param_resp.floats[i];
602  return true;
603  }
604  else
605  {
606  logwarn("Failed to get param: length mismatch");
607  }
608  }
609  return false;
610  }
611  bool getParam(const char* name, char** param, int length = 1, int timeout = 1000)
612  {
613  if (requestParam(name, timeout))
614  {
615  if (length == req_param_resp.strings_length)
616  {
617  //copy it over
618  for (int i = 0; i < length; i++)
619  strcpy(param[i], req_param_resp.strings[i]);
620  return true;
621  }
622  else
623  {
624  logwarn("Failed to get param: length mismatch");
625  }
626  }
627  return false;
628  }
629  bool getParam(const char* name, bool* param, int length = 1, int timeout = 1000)
630  {
631  if (requestParam(name, timeout))
632  {
633  if (length == req_param_resp.ints_length)
634  {
635  //copy it over
636  for (int i = 0; i < length; i++)
637  param[i] = req_param_resp.ints[i];
638  return true;
639  }
640  else
641  {
642  logwarn("Failed to get param: length mismatch");
643  }
644  }
645  return false;
646  }
647 };
648 
649 }
650 
651 #endif
ros::normalizeSecNSec
ROSTIME_DECL void normalizeSecNSec(uint32_t &sec, uint32_t &nsec)
Definition: time.cpp:39
ros::NodeHandle_::nsec_offset
uint32_t nsec_offset
Definition: node_handle.h:115
ros::SPIN_OK
const int SPIN_OK
Definition: node_handle.h:67
ros::NodeHandle_::setSpinTimeout
void setSpinTimeout(const uint32_t &timeout)
Sets the maximum time in millisconds that spinOnce() can work. This will not effect the processing of...
Definition: node_handle.h:163
ros::NodeHandle_::getParam
bool getParam(const char *name, char **param, int length=1, int timeout=1000)
Definition: node_handle.h:611
ros::PROTOCOL_VER1
const uint8_t PROTOCOL_VER1
Definition: node_handle.h:84
ros::NodeHandle_::logwarn
void logwarn(const char *msg)
Definition: node_handle.h:534
ros::MODE_FIRST_FF
const uint8_t MODE_FIRST_FF
Definition: node_handle.h:74
ros::NodeHandle_::syncTime
void syncTime(uint8_t *data)
Definition: node_handle.h:361
ros::NodeHandle_::subscribe
bool subscribe(Subscriber_ &s)
Definition: node_handle.h:413
ros::NodeHandle_::logfatal
void logfatal(const char *msg)
Definition: node_handle.h:542
s
XmlRpcServer s
ros
ros::NodeHandle_::getHardware
Hardware * getHardware()
Definition: node_handle.h:130
ros::MODE_TOPIC_H
const uint8_t MODE_TOPIC_H
Definition: node_handle.h:91
ros::MODE_SIZE_CHECKSUM
const uint8_t MODE_SIZE_CHECKSUM
Definition: node_handle.h:89
ros::NodeHandle_::last_sync_time
uint32_t last_sync_time
Definition: node_handle.h:179
ros::NodeHandle_::spinOnce
virtual int spinOnce() override
Definition: node_handle.h:189
ros::MODE_PROTOCOL_VER
const uint8_t MODE_PROTOCOL_VER
Definition: node_handle.h:83
ros::NodeHandleBase_::connected
virtual bool connected()=0
ros::NodeHandle_::initNode
void initNode(char *portName)
Definition: node_handle.h:146
ros::NodeHandle_::message_in
uint8_t message_in[INPUT_SIZE]
Definition: node_handle.h:120
ros::NodeHandle_::advertise
bool advertise(Publisher &p)
Definition: node_handle.h:397
ros::NodeHandle_::hardware_
Hardware hardware_
Definition: node_handle.h:109
msg.h
ros::NodeHandle_::rt_time
uint32_t rt_time
Definition: node_handle.h:112
ros::PROTOCOL_VER2
const uint8_t PROTOCOL_VER2
Definition: node_handle.h:85
ros::Msg
Definition: msg.h:46
ros::Subscriber_
Definition: subscriber.h:44
ros::NodeHandle_::param_received
bool param_received
Definition: node_handle.h:552
ros::NodeHandle_::publishers
Publisher * publishers[MAX_PUBLISHERS]
Definition: node_handle.h:123
ros::SPIN_TIMEOUT
const int SPIN_TIMEOUT
Definition: node_handle.h:69
ros::NodeHandleBase_::spinOnce
virtual int spinOnce()=0
ros::NodeHandle_::log
void log(char byte, const char *msg)
Definition: node_handle.h:517
ros::NodeHandle_::publish
virtual int publish(int id, const Msg *msg) override
Definition: node_handle.h:476
ros::NodeHandle_::index_
int index_
Definition: node_handle.h:173
ros::MODE_MESSAGE
const uint8_t MODE_MESSAGE
Definition: node_handle.h:92
ros::NodeHandle_::logerror
void logerror(const char *msg)
Definition: node_handle.h:538
ros::MODE_MSG_CHECKSUM
const uint8_t MODE_MSG_CHECKSUM
Definition: node_handle.h:93
ros::NodeHandle_::requestSyncTime
void requestSyncTime()
Definition: node_handle.h:354
ros::NodeHandle_::last_msg_timeout_time
uint32_t last_msg_timeout_time
Definition: node_handle.h:181
ros::NodeHandle_::subscribers
Subscriber_ * subscribers[MAX_SUBSCRIBERS]
Definition: node_handle.h:124
ros::NodeHandle_
Definition: node_handle.h:106
ros::NodeHandle_::initNode
void initNode()
Definition: node_handle.h:136
ros::ServiceClient
Definition: service_client.h:47
ros::Subscriber_::callback
virtual void callback(unsigned char *data)=0
ros::MODE_SIZE_L
const uint8_t MODE_SIZE_L
Definition: node_handle.h:87
ros::SPIN_ERR
const int SPIN_ERR
Definition: node_handle.h:68
ros::SPIN_TIME_RECV
const int SPIN_TIME_RECV
Definition: node_handle.h:71
ros::NodeHandle_::bytes_
int bytes_
Definition: node_handle.h:171
ros::NodeHandle_::negotiateTopics
void negotiateTopics()
Definition: node_handle.h:445
ros::Msg::serialize
virtual int serialize(unsigned char *outbuffer) const =0
ros::Publisher
Definition: publisher.h:45
ros::MODE_SIZE_H
const uint8_t MODE_SIZE_H
Definition: node_handle.h:88
ros::NodeHandle_::spin_timeout_
uint32_t spin_timeout_
Definition: node_handle.h:118
ros::NodeHandle_::req_param_resp
rosserial_msgs::RequestParamResponse req_param_resp
Definition: node_handle.h:553
ros::MODE_TOPIC_L
const uint8_t MODE_TOPIC_L
Definition: node_handle.h:90
ros::SYNC_SECONDS
const uint8_t SYNC_SECONDS
Definition: node_handle.h:73
ros::NodeHandle_::checksum_
int checksum_
Definition: node_handle.h:174
ros::Time
Definition: time.h:46
ros::NodeHandleBase_
Definition: node_handle.h:50
ros::SPIN_TX_STOP_REQUESTED
const int SPIN_TX_STOP_REQUESTED
Definition: node_handle.h:70
ros::NodeHandleBase_::publish
virtual int publish(int id, const Msg *msg)=0
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ros::NodeHandle_::advertiseService
bool advertiseService(ServiceServer< MReq, MRes, ObjT > &srv)
Definition: node_handle.h:429
ros::NodeHandle_::message_out
uint8_t message_out[OUTPUT_SIZE]
Definition: node_handle.h:121
ros::NodeHandle_::logdebug
void logdebug(const char *msg)
Definition: node_handle.h:526
param
T param(const std::string &param_name, const T &default_val)
ros::NodeHandle_::serviceClient
bool serviceClient(ServiceClient< MReq, MRes > &srv)
Definition: node_handle.h:438
ros::NodeHandle_::getParam
bool getParam(const char *name, int *param, int length=1, int timeout=1000)
Definition: node_handle.h:575
ros::ServiceServer
Definition: service_server.h:47
ros::NodeHandle_::getParam
bool getParam(const char *name, float *param, int length=1, int timeout=1000)
Definition: node_handle.h:593
ros::NodeHandle_::connected
virtual bool connected() override
Definition: node_handle.h:345
ros::NodeHandle_::sec_offset
uint32_t sec_offset
Definition: node_handle.h:115
ros::SERIAL_MSG_TIMEOUT
const uint8_t SERIAL_MSG_TIMEOUT
Definition: node_handle.h:96
ros::NodeHandle_::getParam
bool getParam(const char *name, bool *param, int length=1, int timeout=1000)
Definition: node_handle.h:629
ros::NodeHandle_::setNow
void setNow(const Time &new_now)
Definition: node_handle.h:384
ros::NodeHandle_::loginfo
void loginfo(const char *msg)
Definition: node_handle.h:530
ros::NodeHandle_::topic_
int topic_
Definition: node_handle.h:172
ros::NodeHandle_::requestParam
bool requestParam(const char *name, int time_out=1000)
Definition: node_handle.h:555
ros::NodeHandle_::now
Time now()
Definition: node_handle.h:374
ros::NodeHandle_::mode_
int mode_
Definition: node_handle.h:170
ros::NodeHandle_::last_sync_receive_time
uint32_t last_sync_receive_time
Definition: node_handle.h:180
ros::NodeHandle_::configured_
bool configured_
Definition: node_handle.h:176
ros::Subscriber_::id_
int id_
Definition: subscriber.h:51
ros::PROTOCOL_VER
const uint8_t PROTOCOL_VER
Definition: node_handle.h:86


rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Wed Mar 2 2022 00:58:01