Go to the documentation of this file.
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"
98 using rosserial_msgs::TopicInfo;
101 template<
class Hardware,
102 int MAX_SUBSCRIBERS = 25,
103 int MAX_PUBLISHERS = 25,
104 int INPUT_SIZE = 512,
105 int OUTPUT_SIZE = 512>
207 bool tx_stop_requested =
false;
208 bool saw_time_msg =
false;
301 if (
topic_ == TopicInfo::ID_PUBLISHER)
309 else if (
topic_ == TopicInfo::ID_TIME)
314 else if (
topic_ == TopicInfo::ID_PARAMETER_REQUEST)
319 else if (
topic_ == TopicInfo::ID_TX_STOP)
322 tx_stop_requested =
true;
357 publish(TopicInfo::ID_TIME, &t);
367 t.data.sec += offset / 1000;
368 t.data.nsec += (offset % 1000) * 1000000UL;
379 current_time.nsec = (ms % 1000) * 1000000UL +
nsec_offset;
388 nsec_offset = new_now.nsec - (ms % 1000) * 1000000UL + 1000000000UL;
399 for (
int i = 0; i < MAX_PUBLISHERS; i++)
404 p.id_ = i + 100 + MAX_SUBSCRIBERS;
415 for (
int i = 0; i < MAX_SUBSCRIBERS; i++)
428 template<
typename MReq,
typename MRes,
typename ObjT>
437 template<
typename MReq,
typename MRes>
447 rosserial_msgs::TopicInfo ti;
449 for (i = 0; i < MAX_PUBLISHERS; i++)
455 ti.message_type = (
char *)
publishers[i]->msg_->getType();
456 ti.md5sum = (
char *)
publishers[i]->msg_->getMD5();
457 ti.buffer_size = OUTPUT_SIZE;
461 for (i = 0; i < MAX_SUBSCRIBERS; i++)
467 ti.message_type = (
char *)
subscribers[i]->getMsgType();
469 ti.buffer_size = INPUT_SIZE;
495 for (
int i = 5; i < l + 7; i++)
500 if (l <= OUTPUT_SIZE)
507 logerror(
"Message from device dropped: message larger than buffer.");
517 void log(
char byte,
const char * msg)
519 rosserial_msgs::Log l;
522 publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
528 log(rosserial_msgs::Log::ROSDEBUG, msg);
532 log(rosserial_msgs::Log::INFO, msg);
536 log(rosserial_msgs::Log::WARN, msg);
540 log(rosserial_msgs::Log::ERROR, msg);
544 log(rosserial_msgs::Log::FATAL, msg);
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;
567 logwarn(
"Failed to get param: timeout expired");
575 bool getParam(
const char* name,
int* param,
int length = 1,
int timeout = 1000)
582 for (
int i = 0; i <
length; i++)
588 logwarn(
"Failed to get param: length mismatch");
593 bool getParam(
const char* name,
float* param,
int length = 1,
int timeout = 1000)
600 for (
int i = 0; i <
length; i++)
606 logwarn(
"Failed to get param: length mismatch");
611 bool getParam(
const char* name,
char** param,
int length = 1,
int timeout = 1000)
618 for (
int i = 0; i <
length; i++)
624 logwarn(
"Failed to get param: length mismatch");
629 bool getParam(
const char* name,
bool* param,
int length = 1,
int timeout = 1000)
636 for (
int i = 0; i <
length; i++)
642 logwarn(
"Failed to get param: length mismatch");
ROSTIME_DECL void normalizeSecNSec(uint32_t &sec, uint32_t &nsec)
void setSpinTimeout(const uint32_t &timeout)
Sets the maximum time in millisconds that spinOnce() can work. This will not effect the processing of...
bool getParam(const char *name, char **param, int length=1, int timeout=1000)
const uint8_t PROTOCOL_VER1
void logwarn(const char *msg)
const uint8_t MODE_FIRST_FF
void syncTime(uint8_t *data)
bool subscribe(Subscriber_ &s)
void logfatal(const char *msg)
const uint8_t MODE_TOPIC_H
const uint8_t MODE_SIZE_CHECKSUM
virtual int spinOnce() override
const uint8_t MODE_PROTOCOL_VER
virtual bool connected()=0
void initNode(char *portName)
uint8_t message_in[INPUT_SIZE]
bool advertise(Publisher &p)
const uint8_t PROTOCOL_VER2
Publisher * publishers[MAX_PUBLISHERS]
void log(char byte, const char *msg)
virtual int publish(int id, const Msg *msg) override
const uint8_t MODE_MESSAGE
void logerror(const char *msg)
const uint8_t MODE_MSG_CHECKSUM
uint32_t last_msg_timeout_time
Subscriber_ * subscribers[MAX_SUBSCRIBERS]
virtual void callback(unsigned char *data)=0
const uint8_t MODE_SIZE_L
virtual int serialize(unsigned char *outbuffer) const =0
const uint8_t MODE_SIZE_H
rosserial_msgs::RequestParamResponse req_param_resp
const uint8_t MODE_TOPIC_L
const uint8_t SYNC_SECONDS
const int SPIN_TX_STOP_REQUESTED
virtual int publish(int id, const Msg *msg)=0
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
bool advertiseService(ServiceServer< MReq, MRes, ObjT > &srv)
uint8_t message_out[OUTPUT_SIZE]
void logdebug(const char *msg)
T param(const std::string ¶m_name, const T &default_val)
bool serviceClient(ServiceClient< MReq, MRes > &srv)
bool getParam(const char *name, int *param, int length=1, int timeout=1000)
bool getParam(const char *name, float *param, int length=1, int timeout=1000)
virtual bool connected() override
const uint8_t SERIAL_MSG_TIMEOUT
bool getParam(const char *name, bool *param, int length=1, int timeout=1000)
void setNow(const Time &new_now)
void loginfo(const char *msg)
bool requestParam(const char *name, int time_out=1000)
uint32_t last_sync_receive_time
const uint8_t PROTOCOL_VER
rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Wed Mar 2 2022 00:58:01