Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
sick_tim::SickTimCommon Class Reference

#include <sick_tim_common.h>

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

List of all members.

Public Member Functions

void check_angle_range (SickTimConfig &conf)
double get_expected_frequency () const
virtual int init ()
int loopOnce ()
 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.
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

SickTimConfig config_
ros::Publisher datagram_pub_
diagnostic_updater::DiagnosedPublisher
< sensor_msgs::LaserScan > * 
diagnosticPub_
dynamic_reconfigure::Server
< sick_tim::SickTimConfig > 
dynamic_reconfigure_server_
double expectedFrequency_
ros::NodeHandle nh_
AbstractParserparser_
ros::Publisher pub_
bool publish_datagram_

Detailed Description

Definition at line 61 of file sick_tim_common.h.


Constructor & Destructor Documentation

Definition at line 44 of file sick_tim_common.cpp.

Definition at line 86 of file sick_tim_common.cpp.


Member Function Documentation

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

Definition at line 213 of file sick_tim_common.cpp.

virtual int sick_tim::SickTimCommon::close_device ( ) [protected, pure virtual]
virtual int sick_tim::SickTimCommon::get_datagram ( unsigned char *  receiveBuffer,
int  bufferSize,
int *  actual_length 
) [protected, pure 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::SickTimCommonUsb, and sick_tim::SickTimCommonTcp.

Definition at line 71 of file sick_tim_common.h.

int sick_tim::SickTimCommon::init ( ) [virtual]

Definition at line 95 of file sick_tim_common.cpp.

virtual int sick_tim::SickTimCommon::init_device ( ) [protected, pure virtual]
int sick_tim::SickTimCommon::init_scanner ( ) [protected, virtual]

Definition at line 109 of file sick_tim_common.cpp.

Definition at line 176 of file sick_tim_common.cpp.

virtual int sick_tim::SickTimCommon::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.

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

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

int sick_tim::SickTimCommon::stop_scanner ( ) [protected, virtual]

Definition at line 70 of file sick_tim_common.cpp.

void sick_tim::SickTimCommon::update_config ( sick_tim::SickTimConfig &  new_config,
uint32_t  level = 0 
)

Definition at line 222 of file sick_tim_common.cpp.


Member Data Documentation

SickTimConfig sick_tim::SickTimCommon::config_ [private]

Definition at line 109 of file sick_tim_common.h.

Definition at line 101 of file sick_tim_common.h.

Definition at line 105 of file sick_tim_common.h.

Definition at line 95 of file sick_tim_common.h.

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

Definition at line 110 of file sick_tim_common.h.

Definition at line 106 of file sick_tim_common.h.

Definition at line 99 of file sick_tim_common.h.

Definition at line 113 of file sick_tim_common.h.

Definition at line 100 of file sick_tim_common.h.

Definition at line 102 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
autogenerated on Mon Oct 6 2014 07:37:28