#include <sick_mrs1000_communication.h>
Public Member Functions | |
virtual int | loopOnce () |
SickMrs1000Communication (const std::string &hostname, const std::string &port, int &timelimit, ScanAndCloudParser *parser) | |
virtual | ~SickMrs1000Communication () |
Public Member Functions inherited from sick_tim::SickTimCommonTcp | |
SickTimCommonTcp (const std::string &hostname, const std::string &port, int &timelimit, AbstractParser *parser) | |
virtual | ~SickTimCommonTcp () |
Public Member Functions inherited from sick_tim::SickTimCommon | |
void | check_angle_range (SickTimConfig &conf) |
double | get_expected_frequency () const |
virtual int | init () |
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 | init_scanner () |
Protected Member Functions inherited from sick_tim::SickTimCommonTcp | |
void | checkDeadline () |
virtual int | close_device () |
virtual int | get_datagram (unsigned char *receiveBuffer, int bufferSize, int *actual_length) |
Read a datagram from the device. More... | |
void | handleRead (boost::system::error_code error, size_t bytes_transfered) |
virtual int | init_device () |
int | readWithTimeout (size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read=0, bool *exception_occured=0) |
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 () |
Protected Attributes | |
ros::Publisher | cloud_pub_ |
diagnostic_updater::DiagnosedPublisher< sensor_msgs::PointCloud2 > | diagnosed_cloud_publisher_ |
ros::NodeHandle | nh_ |
ScanAndCloudParser * | scan_and_cloud_parser_ |
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_ |
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... | |
Definition at line 48 of file sick_mrs1000_communication.h.
sick_tim::SickMrs1000Communication::SickMrs1000Communication | ( | const std::string & | hostname, |
const std::string & | port, | ||
int & | timelimit, | ||
ScanAndCloudParser * | parser | ||
) |
Definition at line 39 of file sick_mrs1000_communication.cpp.
|
virtual |
Definition at line 54 of file sick_mrs1000_communication.cpp.
|
protectedvirtual |
Reimplemented from sick_tim::SickTimCommon.
Definition at line 135 of file sick_mrs1000_communication.cpp.
|
virtual |
Reimplemented from sick_tim::SickTimCommon.
Definition at line 60 of file sick_mrs1000_communication.cpp.
|
protected |
Definition at line 60 of file sick_mrs1000_communication.h.
|
protected |
Definition at line 62 of file sick_mrs1000_communication.h.
|
protected |
Definition at line 59 of file sick_mrs1000_communication.h.
|
protected |
Definition at line 64 of file sick_mrs1000_communication.h.