61 ROS_ERROR(
"Mockup - sendSOPASCommand(), this should never be called");
103 if (bufferSize < *actual_length + 1)
109 strncpy(reinterpret_cast<char *>(receiveBuffer), &str[0], *actual_length + 1);
117 ROS_WARN(
"Mockup - dropping datagram message");
virtual int init_device()
SickTimCommonMockup(AbstractParser *parser)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply)
Send a SOPAS command to the device and print out the response to the console.
void datagramCB(const std_msgs::String::ConstPtr &msg)
virtual int init_scanner()
virtual int get_datagram(unsigned char *receiveBuffer, int bufferSize, int *actual_length)
Read a datagram from the device.
virtual ~SickTimCommonMockup()
std_msgs::String::ConstPtr datagram_msg_
virtual int close_device()
ROSCPP_DECL void spinOnce()