#include <sick_tim_common_mockup.h>
Public Member Functions | |
SickTimCommonMockup (AbstractParser *parser) | |
virtual | ~SickTimCommonMockup () |
Protected Member Functions | |
virtual int | close_device () |
virtual int | get_datagram (unsigned char *receiveBuffer, int bufferSize, int *actual_length) |
Read a datagram from the device. | |
virtual int | init_device () |
virtual int | init_scanner () |
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. | |
Private Member Functions | |
void | datagramCB (const std_msgs::String::ConstPtr &msg) |
Private Attributes | |
std_msgs::String::ConstPtr | datagram_msg_ |
ros::NodeHandle | nh_ |
ros::Subscriber | sub_ |
Definition at line 51 of file sick_tim_common_mockup.h.
Definition at line 41 of file sick_tim_common_mockup.cpp.
sick_tim::SickTimCommonMockup::~SickTimCommonMockup | ( | ) | [virtual] |
Definition at line 46 of file sick_tim_common_mockup.cpp.
int sick_tim::SickTimCommonMockup::close_device | ( | ) | [protected, virtual] |
Implements sick_tim::SickTimCommon.
Definition at line 50 of file sick_tim_common_mockup.cpp.
void sick_tim::SickTimCommonMockup::datagramCB | ( | const std_msgs::String::ConstPtr & | msg | ) | [private] |
Definition at line 114 of file sick_tim_common_mockup.cpp.
int sick_tim::SickTimCommonMockup::get_datagram | ( | unsigned char * | receiveBuffer, |
int | bufferSize, | ||
int * | actual_length | ||
) | [protected, virtual] |
Read a datagram from the device.
[in] | receiveBuffer | data buffer to fill |
[in] | bufferSize | max data size to write to buffer (result should be 0 terminated) |
[out] | actual_length | the actual amount of data written |
Implements sick_tim::SickTimCommon.
Definition at line 83 of file sick_tim_common_mockup.cpp.
int sick_tim::SickTimCommonMockup::init_device | ( | ) | [protected, virtual] |
Implements sick_tim::SickTimCommon.
Definition at line 68 of file sick_tim_common_mockup.cpp.
int sick_tim::SickTimCommonMockup::init_scanner | ( | ) | [protected, virtual] |
Reimplemented from sick_tim::SickTimCommon.
Definition at line 77 of file sick_tim_common_mockup.cpp.
int sick_tim::SickTimCommonMockup::sendSOPASCommand | ( | const char * | request, |
std::vector< unsigned char > * | reply | ||
) | [protected, virtual] |
Send a SOPAS command to the device and print out the response to the console.
Implements sick_tim::SickTimCommon.
Definition at line 59 of file sick_tim_common_mockup.cpp.
std_msgs::String::ConstPtr sick_tim::SickTimCommonMockup::datagram_msg_ [private] |
Definition at line 79 of file sick_tim_common_mockup.h.
Reimplemented from sick_tim::SickTimCommon.
Definition at line 74 of file sick_tim_common_mockup.h.
Definition at line 77 of file sick_tim_common_mockup.h.