#include <sick_tim3xx_common.h>

| Public Member Functions | |
| void | check_angle_range (SickTim3xxConfig &conf) | 
| double | get_expected_frequency () const | 
| virtual int | init () | 
| int | loopOnce () | 
| SickTim3xxCommon (AbstractParser *parser) | |
| void | update_config (sick_tim3xx::SickTim3xxConfig &new_config, uint32_t level=0) | 
| virtual | ~SickTim3xxCommon () | 
| 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. | |
| virtual int | init_device ()=0 | 
| virtual int | init_scanner () | 
| 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. | |
| virtual int | stop_scanner () | 
| Protected Attributes | |
| diagnostic_updater::Updater | diagnostics_ | 
| Private Attributes | |
| SickTim3xxConfig | config_ | 
| ros::Publisher | datagram_pub_ | 
| diagnostic_updater::DiagnosedPublisher < sensor_msgs::LaserScan > * | diagnosticPub_ | 
| dynamic_reconfigure::Server < sick_tim3xx::SickTim3xxConfig > | dynamic_reconfigure_server_ | 
| double | expectedFrequency_ | 
| ros::NodeHandle | nh_ | 
| AbstractParser * | parser_ | 
| ros::Publisher | pub_ | 
| bool | publish_datagram_ | 
Definition at line 61 of file sick_tim3xx_common.h.
Definition at line 44 of file sick_tim3xx_common.cpp.
| sick_tim3xx::SickTim3xxCommon::~SickTim3xxCommon | ( | ) |  [virtual] | 
Definition at line 86 of file sick_tim3xx_common.cpp.
| void sick_tim3xx::SickTim3xxCommon::check_angle_range | ( | SickTim3xxConfig & | conf | ) | 
Definition at line 213 of file sick_tim3xx_common.cpp.
| virtual int sick_tim3xx::SickTim3xxCommon::close_device | ( | ) |  [protected, pure virtual] | 
Implemented in sick_tim3xx::SickTim3xxCommonUsb, and sick_tim3xx::SickTim3xxCommonTcp.
| virtual int sick_tim3xx::SickTim3xxCommon::get_datagram | ( | unsigned char * | receiveBuffer, | 
| int | bufferSize, | ||
| int * | actual_length | ||
| ) |  [protected, pure 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_tim3xx::SickTim3xxCommonUsb, and sick_tim3xx::SickTim3xxCommonTcp.
| double sick_tim3xx::SickTim3xxCommon::get_expected_frequency | ( | ) | const  [inline] | 
Definition at line 71 of file sick_tim3xx_common.h.
| int sick_tim3xx::SickTim3xxCommon::init | ( | ) |  [virtual] | 
Definition at line 95 of file sick_tim3xx_common.cpp.
| virtual int sick_tim3xx::SickTim3xxCommon::init_device | ( | ) |  [protected, pure virtual] | 
Implemented in sick_tim3xx::SickTim3xxCommonUsb, and sick_tim3xx::SickTim3xxCommonTcp.
| int sick_tim3xx::SickTim3xxCommon::init_scanner | ( | ) |  [protected, virtual] | 
Definition at line 109 of file sick_tim3xx_common.cpp.
Definition at line 176 of file sick_tim3xx_common.cpp.
| virtual int sick_tim3xx::SickTim3xxCommon::sendSOPASCommand | ( | const char * | request, | 
| std::vector< unsigned char > * | reply | ||
| ) |  [protected, pure 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_tim3xx::SickTim3xxCommonUsb, and sick_tim3xx::SickTim3xxCommonTcp.
| int sick_tim3xx::SickTim3xxCommon::stop_scanner | ( | ) |  [protected, virtual] | 
Definition at line 70 of file sick_tim3xx_common.cpp.
| void sick_tim3xx::SickTim3xxCommon::update_config | ( | sick_tim3xx::SickTim3xxConfig & | new_config, | 
| uint32_t | level = 0 | ||
| ) | 
Definition at line 222 of file sick_tim3xx_common.cpp.
| SickTim3xxConfig sick_tim3xx::SickTim3xxCommon::config_  [private] | 
Definition at line 109 of file sick_tim3xx_common.h.
Definition at line 101 of file sick_tim3xx_common.h.
| diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan>* sick_tim3xx::SickTim3xxCommon::diagnosticPub_  [private] | 
Definition at line 105 of file sick_tim3xx_common.h.
Definition at line 95 of file sick_tim3xx_common.h.
| dynamic_reconfigure::Server<sick_tim3xx::SickTim3xxConfig> sick_tim3xx::SickTim3xxCommon::dynamic_reconfigure_server_  [private] | 
Definition at line 110 of file sick_tim3xx_common.h.
| double sick_tim3xx::SickTim3xxCommon::expectedFrequency_  [private] | 
Definition at line 106 of file sick_tim3xx_common.h.
Definition at line 99 of file sick_tim3xx_common.h.
Definition at line 113 of file sick_tim3xx_common.h.
Definition at line 100 of file sick_tim3xx_common.h.
| bool sick_tim3xx::SickTim3xxCommon::publish_datagram_  [private] | 
Definition at line 102 of file sick_tim3xx_common.h.