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 
71 const uint8_t SYNC_SECONDS = 5;
72 const uint8_t MODE_FIRST_FF = 0;
73 /*
74  * The second sync byte is a protocol version. It's value is 0xff for the first
75  * version of the rosserial protocol (used up to hydro), 0xfe for the second version
76  * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable
77  * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy
78  * rosserial_arduino. It must be changed in both this file and in
79  * rosserial_python/src/rosserial_python/SerialClient.py
80  */
81 const uint8_t MODE_PROTOCOL_VER = 1;
82 const uint8_t PROTOCOL_VER1 = 0xff; // through groovy
83 const uint8_t PROTOCOL_VER2 = 0xfe; // in hydro
84 const uint8_t PROTOCOL_VER = PROTOCOL_VER2;
85 const uint8_t MODE_SIZE_L = 2;
86 const uint8_t MODE_SIZE_H = 3;
87 const uint8_t MODE_SIZE_CHECKSUM = 4; // checksum for msg size received from size L and H
88 const uint8_t MODE_TOPIC_L = 5; // waiting for topic id
89 const uint8_t MODE_TOPIC_H = 6;
90 const uint8_t MODE_MESSAGE = 7;
91 const uint8_t MODE_MSG_CHECKSUM = 8; // checksum for msg and topic id
92 
93 
94 const uint8_t SERIAL_MSG_TIMEOUT = 20; // 20 milliseconds to recieve all of message data
95 
96 using rosserial_msgs::TopicInfo;
97 
98 /* Node Handle */
99 template<class Hardware,
100  int MAX_SUBSCRIBERS = 25,
101  int MAX_PUBLISHERS = 25,
102  int INPUT_SIZE = 512,
103  int OUTPUT_SIZE = 512>
105 {
106 protected:
107  Hardware hardware_;
108 
109  /* time used for syncing */
110  uint32_t rt_time;
111 
112  /* used for computing current time */
113  uint32_t sec_offset, nsec_offset;
114 
115  /* Spinonce maximum work timeout */
116  uint32_t spin_timeout_;
117 
118  uint8_t message_in[INPUT_SIZE];
119  uint8_t message_out[OUTPUT_SIZE];
120 
121  Publisher * publishers[MAX_PUBLISHERS];
122  Subscriber_ * subscribers[MAX_SUBSCRIBERS];
123 
124  /*
125  * Setup Functions
126  */
127 public:
128  NodeHandle_() : configured_(false)
129  {
130 
131  for (unsigned int i = 0; i < MAX_PUBLISHERS; i++)
132  publishers[i] = 0;
133 
134  for (unsigned int i = 0; i < MAX_SUBSCRIBERS; i++)
135  subscribers[i] = 0;
136 
137  for (unsigned int i = 0; i < INPUT_SIZE; i++)
138  message_in[i] = 0;
139 
140  for (unsigned int i = 0; i < OUTPUT_SIZE; i++)
141  message_out[i] = 0;
142 
143  req_param_resp.ints_length = 0;
144  req_param_resp.ints = NULL;
145  req_param_resp.floats_length = 0;
146  req_param_resp.floats = NULL;
147  req_param_resp.ints_length = 0;
148  req_param_resp.ints = NULL;
149 
150  spin_timeout_ = 0;
151  }
152 
153  Hardware* getHardware()
154  {
155  return &hardware_;
156  }
157 
158  /* Start serial, initialize buffers */
159  void initNode()
160  {
161  hardware_.init();
162  mode_ = 0;
163  bytes_ = 0;
164  index_ = 0;
165  topic_ = 0;
166  };
167 
168  /* Start a named port, which may be network server IP, initialize buffers */
169  void initNode(char *portName)
170  {
171  hardware_.init(portName);
172  mode_ = 0;
173  bytes_ = 0;
174  index_ = 0;
175  topic_ = 0;
176  };
177 
186  void setSpinTimeout(const uint32_t& timeout)
187  {
188  spin_timeout_ = timeout;
189  }
190 
191 protected:
192  //State machine variables for spinOnce
193  int mode_;
194  int bytes_;
195  int topic_;
196  int index_;
198 
200 
201  /* used for syncing the time */
202  uint32_t last_sync_time;
205 
206 public:
207  /* This function goes in your loop() function, it handles
208  * serial input and callbacks for subscribers.
209  */
210 
211 
212  virtual int spinOnce()
213  {
214  /* restart if timed out */
215  uint32_t c_time = hardware_.time();
216  if ((c_time - last_sync_receive_time) > (SYNC_SECONDS * 2200))
217  {
218  configured_ = false;
219  }
220 
221  /* reset if message has timed out */
222  if (mode_ != MODE_FIRST_FF)
223  {
224  if (c_time > last_msg_timeout_time)
225  {
226  mode_ = MODE_FIRST_FF;
227  }
228  }
229 
230  /* while available buffer, read data */
231  while (true)
232  {
233  // If a timeout has been specified, check how long spinOnce has been running.
234  if (spin_timeout_ > 0)
235  {
236  // If the maximum processing timeout has been exceeded, exit with error.
237  // The next spinOnce can continue where it left off, or optionally
238  // based on the application in use, the hardware buffer could be flushed
239  // and start fresh.
240  if ((hardware_.time() - c_time) > spin_timeout_)
241  {
242  // Exit the spin, processing timeout exceeded.
243  return SPIN_TIMEOUT;
244  }
245  }
246  int data = hardware_.read();
247  if (data < 0)
248  break;
249  checksum_ += data;
250  if (mode_ == MODE_MESSAGE) /* message data being recieved */
251  {
252  message_in[index_++] = data;
253  bytes_--;
254  if (bytes_ == 0) /* is message complete? if so, checksum */
255  mode_ = MODE_MSG_CHECKSUM;
256  }
257  else if (mode_ == MODE_FIRST_FF)
258  {
259  if (data == 0xff)
260  {
261  mode_++;
262  last_msg_timeout_time = c_time + SERIAL_MSG_TIMEOUT;
263  }
264  else if (hardware_.time() - c_time > (SYNC_SECONDS * 1000))
265  {
266  /* We have been stuck in spinOnce too long, return error */
267  configured_ = false;
268  return SPIN_TIMEOUT;
269  }
270  }
271  else if (mode_ == MODE_PROTOCOL_VER)
272  {
273  if (data == PROTOCOL_VER)
274  {
275  mode_++;
276  }
277  else
278  {
279  mode_ = MODE_FIRST_FF;
280  if (configured_ == false)
281  requestSyncTime(); /* send a msg back showing our protocol version */
282  }
283  }
284  else if (mode_ == MODE_SIZE_L) /* bottom half of message size */
285  {
286  bytes_ = data;
287  index_ = 0;
288  mode_++;
289  checksum_ = data; /* first byte for calculating size checksum */
290  }
291  else if (mode_ == MODE_SIZE_H) /* top half of message size */
292  {
293  bytes_ += data << 8;
294  mode_++;
295  }
296  else if (mode_ == MODE_SIZE_CHECKSUM)
297  {
298  if ((checksum_ % 256) == 255)
299  mode_++;
300  else
301  mode_ = MODE_FIRST_FF; /* Abandon the frame if the msg len is wrong */
302  }
303  else if (mode_ == MODE_TOPIC_L) /* bottom half of topic id */
304  {
305  topic_ = data;
306  mode_++;
307  checksum_ = data; /* first byte included in checksum */
308  }
309  else if (mode_ == MODE_TOPIC_H) /* top half of topic id */
310  {
311  topic_ += data << 8;
312  mode_ = MODE_MESSAGE;
313  if (bytes_ == 0)
314  mode_ = MODE_MSG_CHECKSUM;
315  }
316  else if (mode_ == MODE_MSG_CHECKSUM) /* do checksum */
317  {
318  mode_ = MODE_FIRST_FF;
319  if ((checksum_ % 256) == 255)
320  {
321  if (topic_ == TopicInfo::ID_PUBLISHER)
322  {
323  requestSyncTime();
324  negotiateTopics();
325  last_sync_time = c_time;
326  last_sync_receive_time = c_time;
327  return SPIN_ERR;
328  }
329  else if (topic_ == TopicInfo::ID_TIME)
330  {
331  syncTime(message_in);
332  }
333  else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST)
334  {
335  req_param_resp.deserialize(message_in);
336  param_recieved = true;
337  }
338  else if (topic_ == TopicInfo::ID_TX_STOP)
339  {
340  configured_ = false;
341  }
342  else
343  {
344  if (subscribers[topic_ - 100])
345  subscribers[topic_ - 100]->callback(message_in);
346  }
347  }
348  }
349  }
350 
351  /* occasionally sync time */
352  if (configured_ && ((c_time - last_sync_time) > (SYNC_SECONDS * 500)))
353  {
354  requestSyncTime();
355  last_sync_time = c_time;
356  }
357 
358  return SPIN_OK;
359  }
360 
361 
362  /* Are we connected to the PC? */
363  virtual bool connected()
364  {
365  return configured_;
366  };
367 
368  /********************************************************************
369  * Time functions
370  */
371 
373  {
374  std_msgs::Time t;
375  publish(TopicInfo::ID_TIME, &t);
376  rt_time = hardware_.time();
377  }
378 
379  void syncTime(uint8_t * data)
380  {
381  std_msgs::Time t;
382  uint32_t offset = hardware_.time() - rt_time;
383 
384  t.deserialize(data);
385  t.data.sec += offset / 1000;
386  t.data.nsec += (offset % 1000) * 1000000UL;
387 
388  this->setNow(t.data);
389  last_sync_receive_time = hardware_.time();
390  }
391 
393  {
394  uint32_t ms = hardware_.time();
395  Time current_time;
396  current_time.sec = ms / 1000 + sec_offset;
397  current_time.nsec = (ms % 1000) * 1000000UL + nsec_offset;
398  normalizeSecNSec(current_time.sec, current_time.nsec);
399  return current_time;
400  }
401 
402  void setNow(Time & new_now)
403  {
404  uint32_t ms = hardware_.time();
405  sec_offset = new_now.sec - ms / 1000 - 1;
406  nsec_offset = new_now.nsec - (ms % 1000) * 1000000UL + 1000000000UL;
407  normalizeSecNSec(sec_offset, nsec_offset);
408  }
409 
410  /********************************************************************
411  * Topic Management
412  */
413 
414  /* Register a new publisher */
416  {
417  for (int i = 0; i < MAX_PUBLISHERS; i++)
418  {
419  if (publishers[i] == 0) // empty slot
420  {
421  publishers[i] = &p;
422  p.id_ = i + 100 + MAX_SUBSCRIBERS;
423  p.nh_ = this;
424  return true;
425  }
426  }
427  return false;
428  }
429 
430  /* Register a new subscriber */
432  {
433  for (int i = 0; i < MAX_SUBSCRIBERS; i++)
434  {
435  if (subscribers[i] == 0) // empty slot
436  {
437  subscribers[i] = &s;
438  s.id_ = i + 100;
439  return true;
440  }
441  }
442  return false;
443  }
444 
445  /* Register a new Service Server */
446  template<typename MReq, typename MRes, typename ObjT>
448  {
449  bool v = advertise(srv.pub);
450  bool w = subscribe(srv);
451  return v && w;
452  }
453 
454  /* Register a new Service Client */
455  template<typename MReq, typename MRes>
457  {
458  bool v = advertise(srv.pub);
459  bool w = subscribe(srv);
460  return v && w;
461  }
462 
464  {
465  rosserial_msgs::TopicInfo ti;
466  int i;
467  for (i = 0; i < MAX_PUBLISHERS; i++)
468  {
469  if (publishers[i] != 0) // non-empty slot
470  {
471  ti.topic_id = publishers[i]->id_;
472  ti.topic_name = (char *) publishers[i]->topic_;
473  ti.message_type = (char *) publishers[i]->msg_->getType();
474  ti.md5sum = (char *) publishers[i]->msg_->getMD5();
475  ti.buffer_size = OUTPUT_SIZE;
476  publish(publishers[i]->getEndpointType(), &ti);
477  }
478  }
479  for (i = 0; i < MAX_SUBSCRIBERS; i++)
480  {
481  if (subscribers[i] != 0) // non-empty slot
482  {
483  ti.topic_id = subscribers[i]->id_;
484  ti.topic_name = (char *) subscribers[i]->topic_;
485  ti.message_type = (char *) subscribers[i]->getMsgType();
486  ti.md5sum = (char *) subscribers[i]->getMsgMD5();
487  ti.buffer_size = INPUT_SIZE;
488  publish(subscribers[i]->getEndpointType(), &ti);
489  }
490  }
491  configured_ = true;
492  }
493 
494  virtual int publish(int id, const Msg * msg)
495  {
496  if (id >= 100 && !configured_)
497  return 0;
498 
499  /* serialize message */
500  int l = msg->serialize(message_out + 7);
501 
502  /* setup the header */
503  message_out[0] = 0xff;
504  message_out[1] = PROTOCOL_VER;
505  message_out[2] = (uint8_t)((uint16_t)l & 255);
506  message_out[3] = (uint8_t)((uint16_t)l >> 8);
507  message_out[4] = 255 - ((message_out[2] + message_out[3]) % 256);
508  message_out[5] = (uint8_t)((int16_t)id & 255);
509  message_out[6] = (uint8_t)((int16_t)id >> 8);
510 
511  /* calculate checksum */
512  int chk = 0;
513  for (int i = 5; i < l + 7; i++)
514  chk += message_out[i];
515  l += 7;
516  message_out[l++] = 255 - (chk % 256);
517 
518  if (l <= OUTPUT_SIZE)
519  {
520  hardware_.write(message_out, l);
521  return l;
522  }
523  else
524  {
525  logerror("Message from device dropped: message larger than buffer.");
526  return -1;
527  }
528  }
529 
530  /********************************************************************
531  * Logging
532  */
533 
534 protected:
535  void log(char byte, const char * msg)
536  {
537  rosserial_msgs::Log l;
538  l.level = byte;
539  l.msg = (char*)msg;
540  publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
541  }
542 
543 public:
544  void logdebug(const char* msg)
545  {
546  log(rosserial_msgs::Log::ROSDEBUG, msg);
547  }
548  void loginfo(const char * msg)
549  {
550  log(rosserial_msgs::Log::INFO, msg);
551  }
552  void logwarn(const char *msg)
553  {
554  log(rosserial_msgs::Log::WARN, msg);
555  }
556  void logerror(const char*msg)
557  {
558  log(rosserial_msgs::Log::ERROR, msg);
559  }
560  void logfatal(const char*msg)
561  {
562  log(rosserial_msgs::Log::FATAL, msg);
563  }
564 
565  /********************************************************************
566  * Parameters
567  */
568 
569 protected:
571  rosserial_msgs::RequestParamResponse req_param_resp;
572 
573  bool requestParam(const char * name, int time_out = 1000)
574  {
575  param_recieved = false;
576  rosserial_msgs::RequestParamRequest req;
577  req.name = (char*)name;
578  publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
579  uint32_t end_time = hardware_.time() + time_out;
580  while (!param_recieved)
581  {
582  spinOnce();
583  if (hardware_.time() > end_time)
584  {
585  logwarn("Failed to get param: timeout expired");
586  return false;
587  }
588  }
589  return true;
590  }
591 
592 public:
593  bool getParam(const char* name, int* param, int length = 1, int timeout = 1000)
594  {
595  if (requestParam(name, timeout))
596  {
597  if (length == req_param_resp.ints_length)
598  {
599  //copy it over
600  for (int i = 0; i < length; i++)
601  param[i] = req_param_resp.ints[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, float* param, int length = 1, int timeout = 1000)
612  {
613  if (requestParam(name, timeout))
614  {
615  if (length == req_param_resp.floats_length)
616  {
617  //copy it over
618  for (int i = 0; i < length; i++)
619  param[i] = req_param_resp.floats[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, char** param, int length = 1, int timeout = 1000)
630  {
631  if (requestParam(name, timeout))
632  {
633  if (length == req_param_resp.strings_length)
634  {
635  //copy it over
636  for (int i = 0; i < length; i++)
637  strcpy(param[i], req_param_resp.strings[i]);
638  return true;
639  }
640  else
641  {
642  logwarn("Failed to get param: length mismatch");
643  }
644  }
645  return false;
646  }
647  bool getParam(const char* name, bool* param, int length = 1, int timeout = 1000)
648  {
649  if (requestParam(name, timeout))
650  {
651  if (length == req_param_resp.ints_length)
652  {
653  //copy it over
654  for (int i = 0; i < length; i++)
655  param[i] = req_param_resp.ints[i];
656  return true;
657  }
658  else
659  {
660  logwarn("Failed to get param: length mismatch");
661  }
662  }
663  return false;
664  }
665 };
666 
667 }
668 
669 #endif
const uint8_t MODE_TOPIC_L
Definition: node_handle.h:88
void logdebug(const char *msg)
Definition: node_handle.h:544
void logwarn(const char *msg)
Definition: node_handle.h:552
bool advertiseService(ServiceServer< MReq, MRes, ObjT > &srv)
Definition: node_handle.h:447
uint32_t spin_timeout_
Definition: node_handle.h:116
bool getParam(const char *name, char **param, int length=1, int timeout=1000)
Definition: node_handle.h:629
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:186
Definition: time.h:46
const uint8_t MODE_SIZE_L
Definition: node_handle.h:85
const uint8_t PROTOCOL_VER2
Definition: node_handle.h:83
void syncTime(uint8_t *data)
Definition: node_handle.h:379
void log(char byte, const char *msg)
Definition: node_handle.h:535
virtual bool connected()=0
const uint8_t MODE_FIRST_FF
Definition: node_handle.h:72
void logerror(const char *msg)
Definition: node_handle.h:556
const int SPIN_ERR
Definition: node_handle.h:68
uint32_t last_msg_timeout_time
Definition: node_handle.h:204
const uint8_t MODE_PROTOCOL_VER
Definition: node_handle.h:81
uint32_t last_sync_time
Definition: node_handle.h:202
uint32_t rt_time
Definition: node_handle.h:110
void logfatal(const char *msg)
Definition: node_handle.h:560
const uint8_t SYNC_SECONDS
Definition: node_handle.h:71
const uint8_t PROTOCOL_VER
Definition: node_handle.h:84
void negotiateTopics()
Definition: node_handle.h:463
virtual void callback(unsigned char *data)=0
virtual int publish(int id, const Msg *msg)
Definition: node_handle.h:494
bool getParam(const char *name, bool *param, int length=1, int timeout=1000)
Definition: node_handle.h:647
bool subscribe(Subscriber_ &s)
Definition: node_handle.h:431
bool getParam(const char *name, float *param, int length=1, int timeout=1000)
Definition: node_handle.h:611
void loginfo(const char *msg)
Definition: node_handle.h:548
const int SPIN_OK
Definition: node_handle.h:67
const uint8_t MODE_MSG_CHECKSUM
Definition: node_handle.h:91
void subscribe()
virtual int spinOnce()=0
bool getParam(const char *name, int *param, int length=1, int timeout=1000)
Definition: node_handle.h:593
bool requestParam(const char *name, int time_out=1000)
Definition: node_handle.h:573
const uint8_t MODE_SIZE_H
Definition: node_handle.h:86
uint32_t last_sync_receive_time
Definition: node_handle.h:203
void setNow(Time &new_now)
Definition: node_handle.h:402
virtual int publish(int id, const Msg *msg)=0
Hardware hardware_
Definition: node_handle.h:107
const uint8_t MODE_TOPIC_H
Definition: node_handle.h:89
virtual bool connected()
Definition: node_handle.h:363
ROSTIME_DECL void normalizeSecNSec(uint64_t &sec, uint64_t &nsec)
bool advertise(Publisher &p)
Definition: node_handle.h:415
void initNode(char *portName)
Definition: node_handle.h:169
const uint8_t PROTOCOL_VER1
Definition: node_handle.h:82
Hardware * getHardware()
Definition: node_handle.h:153
const uint8_t SERIAL_MSG_TIMEOUT
Definition: node_handle.h:94
const int SPIN_TIMEOUT
Definition: node_handle.h:69
virtual int serialize(unsigned char *outbuffer) const =0
void requestSyncTime()
Definition: node_handle.h:372
const uint8_t MODE_MESSAGE
Definition: node_handle.h:90
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
rosserial_msgs::RequestParamResponse req_param_resp
Definition: node_handle.h:571
const uint8_t MODE_SIZE_CHECKSUM
Definition: node_handle.h:87
uint32_t sec_offset
Definition: node_handle.h:113
Definition: msg.h:45
bool serviceClient(ServiceClient< MReq, MRes > &srv)
Definition: node_handle.h:456
virtual int spinOnce()
Definition: node_handle.h:212


rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Mon Feb 28 2022 23:35:23