36 #include <sensor_msgs/LaserScan.h> 37 #include <boost/asio.hpp> 38 #include <boost/array.hpp> 52 LFCDLaser(
const std::string& port, uint32_t baud_rate, boost::asio::io_service& io);
63 void poll(sensor_msgs::LaserScan::Ptr scan);
uint16_t motor_speed_
current motor speed as reported by the LFCD.
uint16_t rpms
RPMS derived from the rpm bytes in an LFCD packet.
bool shutting_down_
Flag for whether the driver is supposed to be shutting down or not.
boost::asio::serial_port serial_
Actual serial port object for reading/writing to the LFCD Laser Scanner.
LFCDLaser(const std::string &port, uint32_t baud_rate, boost::asio::io_service &io)
Constructs a new LFCDLaser attached to the given serial port.
void close()
Close the driver down and prevent the polling loop from advancing.
std::string port_
The serial port the driver is attached to.
uint32_t baud_rate_
The baud rate for the serial connection.
~LFCDLaser()
Default destructor.
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...