Public Member Functions | Public Attributes | Private Attributes | List of all members
xv_11_laser_driver::XV11Laser Class Reference

#include <xv11_laser.h>

Public Member Functions

void close ()
 Close the driver down and prevent the polling loop from advancing. 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...
 
 XV11Laser (const std::string &port, uint32_t baud_rate, uint32_t firmware, boost::asio::io_service &io)
 Constructs a new XV11Laser attached to the given serial port. More...
 
 ~XV11Laser ()
 Default destructor. More...
 

Public Attributes

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

Private Attributes

uint32_t baud_rate_
 The baud rate for the serial connection. More...
 
uint32_t firmware_
 The firmware version to check. Currently supports two different versions: 1 and 2. More...
 
uint16_t motor_speed_
 current motor speed as reported by the XV11. 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 XV11 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 xv11_laser.h.

Constructor & Destructor Documentation

xv_11_laser_driver::XV11Laser::XV11Laser ( const std::string &  port,
uint32_t  baud_rate,
uint32_t  firmware,
boost::asio::io_service &  io 
)

Constructs a new XV11Laser 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 38 of file xv11_laser.cpp.

xv_11_laser_driver::XV11Laser::~XV11Laser ( )
inline

Default destructor.

Definition at line 55 of file xv11_laser.h.

Member Function Documentation

void xv_11_laser_driver::XV11Laser::close ( )
inline

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

Definition at line 66 of file xv11_laser.h.

void xv_11_laser_driver::XV11Laser::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 43 of file xv11_laser.cpp.

Member Data Documentation

uint32_t xv_11_laser_driver::XV11Laser::baud_rate_
private

The baud rate for the serial connection.

Definition at line 70 of file xv11_laser.h.

uint32_t xv_11_laser_driver::XV11Laser::firmware_
private

The firmware version to check. Currently supports two different versions: 1 and 2.

Definition at line 71 of file xv11_laser.h.

uint16_t xv_11_laser_driver::XV11Laser::motor_speed_
private

current motor speed as reported by the XV11.

Definition at line 75 of file xv11_laser.h.

std::string xv_11_laser_driver::XV11Laser::port_
private

The serial port the driver is attached to.

Definition at line 66 of file xv11_laser.h.

uint16_t xv_11_laser_driver::XV11Laser::rpms

RPMS derived from the rpm bytes in an XV11 packet.

Definition at line 43 of file xv11_laser.h.

boost::asio::serial_port xv_11_laser_driver::XV11Laser::serial_
private

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

Definition at line 74 of file xv11_laser.h.

bool xv_11_laser_driver::XV11Laser::shutting_down_
private

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

Definition at line 73 of file xv11_laser.h.


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


xv_11_laser_driver
Author(s): Eric Perko, Chad Rockey, Rohan Agrawal, Steve 'dillo Okay
autogenerated on Mon Jun 10 2019 15:48:10