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>
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_ |
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 57 of file sicks300.h.
Definition at line 43 of file sicks300.cpp.
Definition at line 116 of file sicks300.cpp.
void SickS300::broadcast_transform | ( | ) |
Broadcasting transform, if endabled.
Definition at line 152 of file sicks300.cpp.
void SickS300::update | ( | void | ) |
Sending laserscan.
Definition at line 120 of file sicks300.cpp.
int SickS300::baud_rate_ [protected] |
Definition at line 88 of file sicks300.h.
int SickS300::connected_ [protected] |
Definition at line 89 of file sicks300.h.
std::string SickS300::device_name_ [protected] |
Definition at line 87 of file sicks300.h.
bool SickS300::reduced_FOV_ [protected] |
Sets the field of view to 180 degree.
Definition at line 82 of file sicks300.h.
sensor_msgs::LaserScan SickS300::scan_data_ [protected] |
Definition at line 75 of file sicks300.h.
ros::Publisher SickS300::scan_data_publisher_ [protected] |
Definition at line 76 of file sicks300.h.
bool SickS300::send_transform_ [protected] |
Send Transform or not.
Definition at line 85 of file sicks300.h.
SerialCommS300 SickS300::serial_comm_ [protected] |
The underlying communications to the laser.
Definition at line 73 of file sicks300.h.
tf::TransformBroadcaster SickS300::tf_broadcaster_ [protected] |
Definition at line 78 of file sicks300.h.
tf::Vector3 SickS300::transform_vector_ [protected] |
Definition at line 79 of file sicks300.h.