#include <hlds_laser_segment_publisher.h>
|
void | close () |
| Close the driver down and prevent the polling loop from advancing. More...
|
|
void | close () |
| Close the driver down and prevent the polling loop from advancing. More...
|
|
| LFCDLaser (const std::string &port, uint32_t baud_rate, boost::asio::io_service &io) |
| Constructs a new LFCDLaser attached to the given serial port. More...
|
|
| LFCDLaser (const std::string &port, uint32_t baud_rate, boost::asio::io_service &io) |
| Constructs a new LFCDLaser attached to the given serial port. More...
|
|
void | poll (sensor_msgs::LaserScan::Ptr scan) |
| Poll the laser to get a new scan. Blocks until a complete new scan is received or close is called. More...
|
|
void | poll (sensor_msgs::LaserScan::Ptr scan) |
| Poll the laser to get a new scan. Blocks until a complete new scan is received or close is called. More...
|
|
| ~LFCDLaser () |
| Default destructor. More...
|
|
| ~LFCDLaser () |
| Default destructor. More...
|
|
|
uint16_t | rpms |
| RPMS derived from the rpm bytes in an LFCD packet. More...
|
|
|
uint32_t | baud_rate_ |
| The baud rate for the serial connection. More...
|
|
uint16_t | motor_speed_ |
| current motor speed as reported by the LFCD. More...
|
|
std::string | port_ |
| The serial port the driver is attached to. More...
|
|
boost::asio::serial_port | serial_ |
| Actual serial port object for reading/writing to the LFCD Laser Scanner. More...
|
|
bool | shutting_down_ |
| Flag for whether the driver is supposed to be shutting down or not. More...
|
|
hls_lfcd_lds::LFCDLaser::LFCDLaser |
( |
const std::string & |
port, |
|
|
uint32_t |
baud_rate, |
|
|
boost::asio::io_service & |
io |
|
) |
| |
Constructs a new LFCDLaser attached to the given serial port.
- Parameters
-
port | The string for the serial port device to attempt to connect to, e.g. "/dev/ttyUSB0" |
baud_rate | The baud rate to open the serial port at. |
io | Boost ASIO IO Service to use when creating the serial port object |
Definition at line 43 of file hlds_laser_publisher.cpp.
hls_lfcd_lds::LFCDLaser::~LFCDLaser |
( |
| ) |
|
hls_lfcd_lds::LFCDLaser::LFCDLaser |
( |
const std::string & |
port, |
|
|
uint32_t |
baud_rate, |
|
|
boost::asio::io_service & |
io |
|
) |
| |
Constructs a new LFCDLaser attached to the given serial port.
- Parameters
-
port | The string for the serial port device to attempt to connect to, e.g. "/dev/ttyUSB0" |
baud_rate | The baud rate to open the serial port at. |
io | Boost ASIO IO Service to use when creating the serial port object |
hls_lfcd_lds::LFCDLaser::~LFCDLaser |
( |
| ) |
|
void hls_lfcd_lds::LFCDLaser::close |
( |
| ) |
|
|
inline |
void hls_lfcd_lds::LFCDLaser::close |
( |
| ) |
|
|
inline |
Close the driver down and prevent the polling loop from advancing.
Definition at line 68 of file lfcd_laser.h.
void hls_lfcd_lds::LFCDLaser::poll |
( |
sensor_msgs::LaserScan::Ptr |
scan | ) |
|
Poll the laser to get a new scan. Blocks until a complete new scan is received or close is called.
- Parameters
-
scan | LaserScan message pointer to fill in with the scan. The caller is responsible for filling in the ROS timestamp and frame_id |
void hls_lfcd_lds::LFCDLaser::poll |
( |
sensor_msgs::LaserScan::Ptr |
scan | ) |
|
Poll the laser to get a new scan. Blocks until a complete new scan is received or close is called.
- Parameters
-
scan | LaserScan message pointer to fill in with the scan. The caller is responsible for filling in the ROS timestamp and frame_id |
Definition at line 57 of file hlds_laser_publisher.cpp.
uint32_t hls_lfcd_lds::LFCDLaser::baud_rate_ |
|
private |
uint16_t hls_lfcd_lds::LFCDLaser::motor_speed_ |
|
private |
std::string hls_lfcd_lds::LFCDLaser::port_ |
|
private |
uint16_t hls_lfcd_lds::LFCDLaser::rpms |
boost::asio::serial_port hls_lfcd_lds::LFCDLaser::serial_ |
|
private |
bool hls_lfcd_lds::LFCDLaser::shutting_down_ |
|
private |
The documentation for this class was generated from the following files: