Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Attributes | List of all members
sick_tim::SickTimCommon Class Referenceabstract

#include <sick_tim_common.h>

Inheritance diagram for sick_tim::SickTimCommon:
Inheritance graph
[legend]

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_
 
AbstractParserparser_
 
ros::Publisher pub_
 

Detailed Description

Definition at line 63 of file sick_tim_common.h.

Constructor & Destructor Documentation

sick_tim::SickTimCommon::SickTimCommon ( AbstractParser parser)

Definition at line 47 of file sick_tim_common.cpp.

sick_tim::SickTimCommon::~SickTimCommon ( )
virtual

Definition at line 137 of file sick_tim_common.cpp.

Member Function Documentation

void sick_tim::SickTimCommon::check_angle_range ( SickTimConfig &  conf)

Definition at line 340 of file sick_tim_common.cpp.

virtual int sick_tim::SickTimCommon::close_device ( )
protectedpure virtual
virtual int sick_tim::SickTimCommon::get_datagram ( unsigned char *  receiveBuffer,
int  bufferSize,
int *  actual_length 
)
protectedpure virtual

Read a datagram from the device.

Parameters
[in]receiveBufferdata buffer to fill
[in]bufferSizemax data size to write to buffer (result should be 0 terminated)
[out]actual_lengththe actual amount of data written

Implemented in sick_tim::SickTimCommonMockup, sick_tim::SickTimCommonUsb, and sick_tim::SickTimCommonTcp.

double sick_tim::SickTimCommon::get_expected_frequency ( ) const
inline

Definition at line 73 of file sick_tim_common.h.

int sick_tim::SickTimCommon::init ( )
virtual

Definition at line 145 of file sick_tim_common.cpp.

virtual int sick_tim::SickTimCommon::init_device ( )
protectedpure virtual
int sick_tim::SickTimCommon::init_scanner ( )
protectedvirtual
bool sick_tim::SickTimCommon::isCompatibleDevice ( const std::string  identStr) const
protected

Definition at line 270 of file sick_tim_common.cpp.

int sick_tim::SickTimCommon::loopOnce ( )
virtual

Reimplemented in sick_tim::SickMrs1000Communication.

Definition at line 290 of file sick_tim_common.cpp.

bool sick_tim::SickTimCommon::rebootScanner ( )
virtual

Send a SOPAS command to the scanner that should cause a soft reset.

Returns
true if reboot command was accepted, false otherwise

Definition at line 89 of file sick_tim_common.cpp.

std::string sick_tim::SickTimCommon::replyToString ( const std::vector< unsigned char > &  reply)
staticprotected

Converts reply from sendSOPASCommand to string.

Parameters
[in]replyreply from sendSOPASCommand
Returns
reply as string with special characters stripped out

Definition at line 257 of file sick_tim_common.cpp.

virtual int sick_tim::SickTimCommon::sendSOPASCommand ( const char *  request,
std::vector< unsigned char > *  reply 
)
protectedpure virtual

Send a SOPAS command to the device and print out the response to the console.

Parameters
[in]requestthe command to send.
[out]replyif not NULL, will be filled with the reply package to the command.

Implemented in sick_tim::SickTimCommonMockup, sick_tim::SickTimCommonUsb, and sick_tim::SickTimCommonTcp.

int sick_tim::SickTimCommon::stop_scanner ( )
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.

Member Data Documentation

SickTimConfig sick_tim::SickTimCommon::config_
protected

Definition at line 115 of file sick_tim_common.h.

ros::Publisher sick_tim::SickTimCommon::datagram_pub_
protected

Definition at line 117 of file sick_tim_common.h.

diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan>* sick_tim::SickTimCommon::diagnosticPub_
protected

Definition at line 120 of file sick_tim_common.h.

diagnostic_updater::Updater sick_tim::SickTimCommon::diagnostics_
protected

Definition at line 112 of file sick_tim_common.h.

dynamic_reconfigure::Server<sick_tim::SickTimConfig> sick_tim::SickTimCommon::dynamic_reconfigure_server_
private

Definition at line 129 of file sick_tim_common.h.

double sick_tim::SickTimCommon::expectedFrequency_
protected

Definition at line 121 of file sick_tim_common.h.

ros::NodeHandle sick_tim::SickTimCommon::nh_
private

Definition at line 125 of file sick_tim_common.h.

AbstractParser* sick_tim::SickTimCommon::parser_
private

Definition at line 132 of file sick_tim_common.h.

ros::Publisher sick_tim::SickTimCommon::pub_
private

Definition at line 126 of file sick_tim_common.h.

bool sick_tim::SickTimCommon::publish_datagram_
protected

Definition at line 116 of file sick_tim_common.h.


The documentation for this class was generated from the following files:


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther , Sebastian Pütz
autogenerated on Tue May 7 2019 03:13:47