#include <sick_tim_common.h>
Public Member Functions | |
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 ()=0 |
virtual int | get_datagram (unsigned char *receiveBuffer, int bufferSize, int *actual_length)=0 |
Read a datagram from the device. More... | |
virtual int | init_device ()=0 |
virtual int | init_scanner () |
bool | isCompatibleDevice (const std::string identStr) const |
virtual int | sendSOPASCommand (const char *request, std::vector< unsigned char > *reply)=0 |
Send a SOPAS command to the device and print out the response to the console. More... | |
virtual int | stop_scanner () |
Static Protected Member Functions | |
static std::string | replyToString (const std::vector< unsigned char > &reply) |
Converts reply from sendSOPASCommand to string. More... | |
Protected Attributes | |
SickTimConfig | config_ |
ros::Publisher | datagram_pub_ |
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * | diagnosticPub_ |
diagnostic_updater::Updater | diagnostics_ |
double | expectedFrequency_ |
bool | publish_datagram_ |
Private Attributes | |
dynamic_reconfigure::Server< sick_tim::SickTimConfig > | dynamic_reconfigure_server_ |
ros::NodeHandle | nh_ |
AbstractParser * | parser_ |
ros::Publisher | pub_ |
Definition at line 63 of file sick_tim_common.h.
sick_tim::SickTimCommon::SickTimCommon | ( | AbstractParser * | parser | ) |
Definition at line 47 of file sick_tim_common.cpp.
|
virtual |
Definition at line 137 of file sick_tim_common.cpp.
void sick_tim::SickTimCommon::check_angle_range | ( | SickTimConfig & | conf | ) |
Definition at line 340 of file sick_tim_common.cpp.
|
protectedpure virtual |
Implemented in sick_tim::SickTimCommonMockup, sick_tim::SickTimCommonUsb, and sick_tim::SickTimCommonTcp.
|
protectedpure 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 |
Implemented in sick_tim::SickTimCommonMockup, sick_tim::SickTimCommonUsb, and sick_tim::SickTimCommonTcp.
|
inline |
Definition at line 73 of file sick_tim_common.h.
|
virtual |
Definition at line 145 of file sick_tim_common.cpp.
|
protectedpure virtual |
Implemented in sick_tim::SickTimCommonUsb, sick_tim::SickTimCommonMockup, and sick_tim::SickTimCommonTcp.
|
protectedvirtual |
Reimplemented in sick_tim::SickMrs1000Communication, and sick_tim::SickTimCommonMockup.
Definition at line 159 of file sick_tim_common.cpp.
|
protected |
Definition at line 270 of file sick_tim_common.cpp.
|
virtual |
Reimplemented in sick_tim::SickMrs1000Communication.
Definition at line 290 of file sick_tim_common.cpp.
|
virtual |
Send a SOPAS command to the scanner that should cause a soft reset.
Definition at line 89 of file sick_tim_common.cpp.
|
staticprotected |
Converts reply from sendSOPASCommand to string.
[in] | reply | reply from sendSOPASCommand |
Definition at line 257 of file sick_tim_common.cpp.
|
protectedpure virtual |
Send a SOPAS command to the device and print out the response to the console.
[in] | request | the command to send. |
[out] | reply | if not NULL, will be filled with the reply package to the command. |
Implemented in sick_tim::SickTimCommonMockup, sick_tim::SickTimCommonUsb, and sick_tim::SickTimCommonTcp.
|
protectedvirtual |
Definition at line 73 of file sick_tim_common.cpp.
void sick_tim::SickTimCommon::update_config | ( | sick_tim::SickTimConfig & | new_config, |
uint32_t | level = 0 |
||
) |
Definition at line 349 of file sick_tim_common.cpp.
|
protected |
Definition at line 115 of file sick_tim_common.h.
|
protected |
Definition at line 117 of file sick_tim_common.h.
|
protected |
Definition at line 120 of file sick_tim_common.h.
|
protected |
Definition at line 112 of file sick_tim_common.h.
|
private |
Definition at line 129 of file sick_tim_common.h.
|
protected |
Definition at line 121 of file sick_tim_common.h.
|
private |
Definition at line 125 of file sick_tim_common.h.
|
private |
Definition at line 132 of file sick_tim_common.h.
|
private |
Definition at line 126 of file sick_tim_common.h.
|
protected |
Definition at line 116 of file sick_tim_common.h.