Public Member Functions | Public Attributes | Private Attributes | List of all members
hls_lfcd_lds2::LFCDLaser Class Reference

#include <lfcd_lds2.h>

Public Member Functions

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...
 
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...
 

Public Attributes

uint16_t rpms
 RPMS derived from the rpm bytes in an LFCD packet. More...
 

Private Attributes

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...
 

Detailed Description

Definition at line 41 of file lfcd_lds2.h.

Constructor & Destructor Documentation

hls_lfcd_lds2::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
portThe string for the serial port device to attempt to connect to, e.g. "/dev/ttyUSB0"
baud_rateThe baud rate to open the serial port at.
ioBoost ASIO IO Service to use when creating the serial port object

Definition at line 42 of file hlds_lds2_publisher.cpp.

hls_lfcd_lds2::LFCDLaser::~LFCDLaser ( )

Default destructor.

Definition at line 50 of file hlds_lds2_publisher.cpp.

Member Function Documentation

void hls_lfcd_lds2::LFCDLaser::close ( )
inline

Close the driver down and prevent the polling loop from advancing.

Definition at line 67 of file lfcd_lds2.h.

void hls_lfcd_lds2::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
scanLaserScan message pointer to fill in with the scan. The caller is responsible for filling in the ROS timestamp and frame_id

Definition at line 56 of file hlds_lds2_publisher.cpp.

Member Data Documentation

uint32_t hls_lfcd_lds2::LFCDLaser::baud_rate_
private

The baud rate for the serial connection.

Definition at line 71 of file lfcd_lds2.h.

uint16_t hls_lfcd_lds2::LFCDLaser::motor_speed_
private

current motor speed as reported by the LFCD.

Definition at line 74 of file lfcd_lds2.h.

std::string hls_lfcd_lds2::LFCDLaser::port_
private

The serial port the driver is attached to.

Definition at line 70 of file lfcd_lds2.h.

uint16_t hls_lfcd_lds2::LFCDLaser::rpms

RPMS derived from the rpm bytes in an LFCD packet.

Definition at line 44 of file lfcd_lds2.h.

boost::asio::serial_port hls_lfcd_lds2::LFCDLaser::serial_
private

Actual serial port object for reading/writing to the LFCD Laser Scanner.

Definition at line 73 of file lfcd_lds2.h.

bool hls_lfcd_lds2::LFCDLaser::shutting_down_
private

Flag for whether the driver is supposed to be shutting down or not.

Definition at line 72 of file lfcd_lds2.h.


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


hls-lfcd-lds2-driver
Author(s): SP Kong, Jeehoon Yang
autogenerated on Mon Jun 10 2019 13:24:10