#include <sick_tim_common_mockup.h>
Public Member Functions | |
SickTimCommonMockup (AbstractParser *parser) | |
virtual | ~SickTimCommonMockup () |
Public Member Functions inherited from sick_tim::SickTimCommon | |
void | check_angle_range (SickTimConfig &conf) |
double | get_expected_frequency () const |
virtual int | init () |
virtual int | loopOnce () |
virtual bool | rebootScanner () |
Send a SOPAS command to the scanner that should cause a soft reset. More... | |
SickTimCommon (AbstractParser *parser) | |
void | update_config (sick_tim::SickTimConfig &new_config, uint32_t level=0) |
virtual | ~SickTimCommon () |
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. More... | |
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. More... | |
Protected Member Functions inherited from sick_tim::SickTimCommon | |
bool | isCompatibleDevice (const std::string identStr) const |
virtual int | stop_scanner () |
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_ |
Additional Inherited Members | |
Static Protected Member Functions inherited from sick_tim::SickTimCommon | |
static std::string | replyToString (const std::vector< unsigned char > &reply) |
Converts reply from sendSOPASCommand to string. More... | |
Protected Attributes inherited from sick_tim::SickTimCommon | |
SickTimConfig | config_ |
ros::Publisher | datagram_pub_ |
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * | diagnosticPub_ |
diagnostic_updater::Updater | diagnostics_ |
double | expectedFrequency_ |
bool | publish_datagram_ |
Definition at line 51 of file sick_tim_common_mockup.h.
sick_tim::SickTimCommonMockup::SickTimCommonMockup | ( | AbstractParser * | parser | ) |
Definition at line 41 of file sick_tim_common_mockup.cpp.
|
virtual |
Definition at line 46 of file sick_tim_common_mockup.cpp.
|
protectedvirtual |
Implements sick_tim::SickTimCommon.
Definition at line 50 of file sick_tim_common_mockup.cpp.
|
private |
Definition at line 114 of file sick_tim_common_mockup.cpp.
|
protectedvirtual |
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.
|
protectedvirtual |
Implements sick_tim::SickTimCommon.
Definition at line 68 of file sick_tim_common_mockup.cpp.
|
protectedvirtual |
Reimplemented from sick_tim::SickTimCommon.
Definition at line 77 of file sick_tim_common_mockup.cpp.
|
protectedvirtual |
Send a SOPAS command to the device and print out the response to the console.
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.
|
private |
Definition at line 79 of file sick_tim_common_mockup.h.
|
private |
Definition at line 74 of file sick_tim_common_mockup.h.
|
private |
Definition at line 77 of file sick_tim_common_mockup.h.