Class LFCDLaser

Class Documentation

class hls_lfcd_lds::LFCDLaser

Public Functions

LFCDLaser(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

inline ~LFCDLaser()

Default destructor.

void poll()

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 close()

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

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

~LFCDLaser()

Default destructor.

void poll(sensor_msgs::msg::LaserScan::SharedPtr 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

inline void close()

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

Public Members

uint16_t rpms

RPMS derived from the rpm bytes in an LFCD packet.