Public Member Functions | Protected Attributes
SickS300 Class Reference

uses SerialCommS300 to connect to Sick S300 laserscanner, read data and publishes to a laserscan-topic. It also includes a transform publisher to send the appropriate transform for the laser More...

#include <sicks300.h>

List of all members.

Public Member Functions

void broadcast_transform ()
 Broadcasting transform, if endabled.
 SickS300 ()
void update ()
 Sending laserscan.
 ~SickS300 ()

Protected Attributes

int baud_rate_
int connected_
std::string device_name_
bool reduced_FOV_
 Sets the field of view to 180 degree.
sensor_msgs::LaserScan scan_data_
ros::Publisher scan_data_publisher_
bool send_transform_
 Send Transform or not.
SerialCommS300 serial_comm_
 The underlying communications to the laser.
tf::TransformBroadcaster tf_broadcaster_
tf::Vector3 transform_vector_

Detailed Description

uses SerialCommS300 to connect to Sick S300 laserscanner, read data and publishes to a laserscan-topic. It also includes a transform publisher to send the appropriate transform for the laser

Definition at line 62 of file sicks300.h.


Constructor & Destructor Documentation

Definition at line 48 of file sicks300.cpp.

Definition at line 121 of file sicks300.cpp.


Member Function Documentation

Broadcasting transform, if endabled.

Definition at line 157 of file sicks300.cpp.

void SickS300::update ( )

Sending laserscan.

Definition at line 125 of file sicks300.cpp.


Member Data Documentation

int SickS300::baud_rate_ [protected]

Definition at line 93 of file sicks300.h.

int SickS300::connected_ [protected]

Definition at line 94 of file sicks300.h.

std::string SickS300::device_name_ [protected]

Definition at line 92 of file sicks300.h.

bool SickS300::reduced_FOV_ [protected]

Sets the field of view to 180 degree.

Definition at line 87 of file sicks300.h.

sensor_msgs::LaserScan SickS300::scan_data_ [protected]

Definition at line 80 of file sicks300.h.

Definition at line 81 of file sicks300.h.

bool SickS300::send_transform_ [protected]

Send Transform or not.

Definition at line 90 of file sicks300.h.

The underlying communications to the laser.

Definition at line 78 of file sicks300.h.

Definition at line 83 of file sicks300.h.

tf::Vector3 SickS300::transform_vector_ [protected]

Definition at line 84 of file sicks300.h.


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


sicks300
Author(s): Dimitri Bohlender
autogenerated on Mon Oct 6 2014 07:37:46