35 #ifndef ROS_NODE_HANDLE_H_ 36 #define ROS_NODE_HANDLE_H_ 40 #include "std_msgs/Time.h" 41 #include "rosserial_msgs/TopicInfo.h" 42 #include "rosserial_msgs/Log.h" 43 #include "rosserial_msgs/RequestParam.h" 53 virtual int publish(
int id,
const Msg* msg) = 0;
59 #include "ros/publisher.h" 60 #include "ros/subscriber.h" 61 #include "ros/service_server.h" 62 #include "ros/service_client.h" 96 using rosserial_msgs::TopicInfo;
99 template<
class Hardware,
100 int MAX_SUBSCRIBERS = 25,
101 int MAX_PUBLISHERS = 25,
102 int INPUT_SIZE = 512,
103 int OUTPUT_SIZE = 512>
118 uint8_t message_in[INPUT_SIZE];
119 uint8_t message_out[OUTPUT_SIZE];
131 for (
unsigned int i = 0; i < MAX_PUBLISHERS; i++)
134 for (
unsigned int i = 0; i < MAX_SUBSCRIBERS; i++)
137 for (
unsigned int i = 0; i < INPUT_SIZE; i++)
140 for (
unsigned int i = 0; i < OUTPUT_SIZE; i++)
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;
171 hardware_.init(portName);
188 spin_timeout_ = timeout;
215 uint32_t c_time = hardware_.time();
216 if ((c_time - last_sync_receive_time) > (SYNC_SECONDS * 2200))
222 if (mode_ != MODE_FIRST_FF)
224 if (c_time > last_msg_timeout_time)
234 if (spin_timeout_ > 0)
240 if ((hardware_.time() - c_time) > spin_timeout_)
246 int data = hardware_.read();
250 if (mode_ == MODE_MESSAGE)
252 message_in[index_++] = data;
257 else if (mode_ == MODE_FIRST_FF)
264 else if (hardware_.time() - c_time > (SYNC_SECONDS * 1000))
271 else if (mode_ == MODE_PROTOCOL_VER)
273 if (data == PROTOCOL_VER)
280 if (configured_ ==
false)
284 else if (mode_ == MODE_SIZE_L)
291 else if (mode_ == MODE_SIZE_H)
296 else if (mode_ == MODE_SIZE_CHECKSUM)
298 if ((checksum_ % 256) == 255)
303 else if (mode_ == MODE_TOPIC_L)
309 else if (mode_ == MODE_TOPIC_H)
316 else if (mode_ == MODE_MSG_CHECKSUM)
319 if ((checksum_ % 256) == 255)
321 if (topic_ == TopicInfo::ID_PUBLISHER)
325 last_sync_time = c_time;
326 last_sync_receive_time = c_time;
329 else if (topic_ == TopicInfo::ID_TIME)
331 syncTime(message_in);
333 else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST)
335 req_param_resp.deserialize(message_in);
336 param_recieved =
true;
338 else if (topic_ == TopicInfo::ID_TX_STOP)
344 if (subscribers[topic_ - 100])
345 subscribers[topic_ - 100]->
callback(message_in);
352 if (configured_ && ((c_time - last_sync_time) > (SYNC_SECONDS * 500)))
355 last_sync_time = c_time;
375 publish(TopicInfo::ID_TIME, &t);
376 rt_time = hardware_.time();
382 uint32_t offset = hardware_.time() - rt_time;
385 t.data.sec += offset / 1000;
386 t.data.nsec += (offset % 1000) * 1000000UL;
388 this->setNow(t.data);
389 last_sync_receive_time = hardware_.time();
394 uint32_t ms = hardware_.time();
396 current_time.sec = ms / 1000 + sec_offset;
397 current_time.nsec = (ms % 1000) * 1000000UL + nsec_offset;
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;
417 for (
int i = 0; i < MAX_PUBLISHERS; i++)
419 if (publishers[i] == 0)
422 p.id_ = i + 100 + MAX_SUBSCRIBERS;
431 template<
typename SubscriberT>
434 for (
int i = 0; i < MAX_SUBSCRIBERS; i++)
436 if (subscribers[i] == 0)
447 template<
typename MReq,
typename MRes,
typename ObjT>
450 bool v = advertise(srv.pub);
451 for (
int i = 0; i < MAX_SUBSCRIBERS; i++)
453 if (subscribers[i] == 0)
464 template<
typename MReq,
typename MRes>
467 bool v = advertise(srv.pub);
468 for (
int i = 0; i < MAX_SUBSCRIBERS; i++)
470 if (subscribers[i] == 0)
482 rosserial_msgs::TopicInfo ti;
484 for (i = 0; i < MAX_PUBLISHERS; i++)
486 if (publishers[i] != 0)
488 ti.topic_id = publishers[i]->id_;
489 ti.topic_name = (
char *) publishers[i]->topic_;
490 ti.message_type = (
char *) publishers[i]->msg_->getType();
491 ti.md5sum = (
char *) publishers[i]->msg_->getMD5();
492 ti.buffer_size = OUTPUT_SIZE;
493 publish(publishers[i]->getEndpointType(), &ti);
496 for (i = 0; i < MAX_SUBSCRIBERS; i++)
498 if (subscribers[i] != 0)
500 ti.topic_id = subscribers[i]->
id_;
501 ti.topic_name = (
char *) subscribers[i]->topic_;
502 ti.message_type = (
char *) subscribers[i]->getMsgType();
503 ti.md5sum = (
char *) subscribers[i]->getMsgMD5();
504 ti.buffer_size = INPUT_SIZE;
505 publish(subscribers[i]->getEndpointType(), &ti);
513 if (
id >= 100 && !configured_)
520 message_out[0] = 0xff;
522 message_out[2] = (uint8_t)((uint16_t)l & 255);
523 message_out[3] = (uint8_t)((uint16_t)l >> 8);
524 message_out[4] = 255 - ((message_out[2] + message_out[3]) % 256);
525 message_out[5] = (uint8_t)((int16_t)
id & 255);
526 message_out[6] = (uint8_t)((int16_t)
id >> 8);
530 for (
int i = 5; i < l + 7; i++)
531 chk += message_out[i];
533 message_out[l++] = 255 - (chk % 256);
535 if (l <= OUTPUT_SIZE)
537 hardware_.write(message_out, l);
542 logerror(
"Message from device dropped: message larger than buffer.");
552 void log(
char byte,
const char * msg)
554 rosserial_msgs::Log l;
557 publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
563 log(rosserial_msgs::Log::ROSDEBUG, msg);
567 log(rosserial_msgs::Log::INFO, msg);
571 log(rosserial_msgs::Log::WARN, msg);
575 log(rosserial_msgs::Log::ERROR, msg);
579 log(rosserial_msgs::Log::FATAL, msg);
592 param_recieved =
false;
593 rosserial_msgs::RequestParamRequest req;
594 req.name = (
char*)name;
595 publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
596 uint32_t end_time = hardware_.time() + time_out;
597 while (!param_recieved)
600 if (hardware_.time() > end_time)
602 logwarn(
"Failed to get param: timeout expired");
610 bool getParam(
const char* name,
int* param,
int length = 1,
int timeout = 1000)
612 if (requestParam(name, timeout))
614 if (
length == req_param_resp.ints_length)
617 for (
int i = 0; i <
length; i++)
618 param[i] = req_param_resp.ints[i];
623 logwarn(
"Failed to get param: length mismatch");
628 bool getParam(
const char* name,
float* param,
int length = 1,
int timeout = 1000)
630 if (requestParam(name, timeout))
632 if (
length == req_param_resp.floats_length)
635 for (
int i = 0; i <
length; i++)
636 param[i] = req_param_resp.floats[i];
641 logwarn(
"Failed to get param: length mismatch");
646 bool getParam(
const char* name,
char** param,
int length = 1,
int timeout = 1000)
648 if (requestParam(name, timeout))
650 if (
length == req_param_resp.strings_length)
653 for (
int i = 0; i <
length; i++)
654 strcpy(param[i], req_param_resp.strings[i]);
659 logwarn(
"Failed to get param: length mismatch");
664 bool getParam(
const char* name,
bool* param,
int length = 1,
int timeout = 1000)
666 if (requestParam(name, timeout))
668 if (
length == req_param_resp.ints_length)
671 for (
int i = 0; i <
length; i++)
672 param[i] = req_param_resp.ints[i];
677 logwarn(
"Failed to get param: length mismatch");
const uint8_t MODE_TOPIC_L
void logdebug(const char *msg)
void logwarn(const char *msg)
bool advertiseService(ServiceServer< MReq, MRes, ObjT > &srv)
bool getParam(const char *name, char **param, int length=1, int timeout=1000)
void setSpinTimeout(const uint32_t &timeout)
Sets the maximum time in millisconds that spinOnce() can work. This will not effect the processing of...
const uint8_t MODE_SIZE_L
const uint8_t PROTOCOL_VER2
void syncTime(uint8_t *data)
void log(char byte, const char *msg)
virtual bool connected()=0
const uint8_t MODE_FIRST_FF
void logerror(const char *msg)
uint32_t last_msg_timeout_time
const uint8_t MODE_PROTOCOL_VER
void logfatal(const char *msg)
const uint8_t SYNC_SECONDS
const uint8_t PROTOCOL_VER
virtual void callback(unsigned char *data)=0
virtual int publish(int id, const Msg *msg)
bool getParam(const char *name, bool *param, int length=1, int timeout=1000)
bool subscribe(SubscriberT &s)
bool getParam(const char *name, float *param, int length=1, int timeout=1000)
void loginfo(const char *msg)
const uint8_t MODE_MSG_CHECKSUM
bool getParam(const char *name, int *param, int length=1, int timeout=1000)
bool requestParam(const char *name, int time_out=1000)
const uint8_t MODE_SIZE_H
uint32_t last_sync_receive_time
void setNow(Time &new_now)
virtual int publish(int id, const Msg *msg)=0
ROSTIME_DECL void normalizeSecNSec(uint32_t &sec, uint32_t &nsec)
const uint8_t MODE_TOPIC_H
bool advertise(Publisher &p)
void initNode(char *portName)
const uint8_t PROTOCOL_VER1
const uint8_t SERIAL_MSG_TIMEOUT
virtual int serialize(unsigned char *outbuffer) const =0
const uint8_t MODE_MESSAGE
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
rosserial_msgs::RequestParamResponse req_param_resp
const uint8_t MODE_SIZE_CHECKSUM
bool serviceClient(ServiceClient< MReq, MRes > &srv)