Class LMS1xx

Class Documentation

class LMS1xx

Class responsible for communicating with LMS1xx device.

Author

Konrad Banachowicz

Public Functions

LMS1xx()
virtual ~LMS1xx()
void connect(std::string host, int port = 2111)

Connect to LMS1xx.

Parameters:
  • hostLMS1xx host name or ip address.

  • portLMS1xx port number.

void disconnect()

Disconnect from LMS1xx device.

bool isConnected()

Get status of connection.

Returns:

connected or not.

void startMeas()

Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring.

void stopMeas()

Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring.

status_t queryStatus()

Get current status of LMS1xx device.

Returns:

status of LMS1xx device.

void login()

Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.

scanCfg getScanCfg() const

Get current scan configuration. Get scan configuration :

  • scanning frequency.

  • scanning resolution.

  • start angle.

  • stop angle.

Returns:

scanCfg structure.

void setScanCfg(const scanCfg &cfg)

Set scan configuration. Get scan configuration :

  • scanning frequency.

  • scanning resolution.

  • start angle.

  • stop angle.

Parameters:

cfg – structure containing scan configuration.

void setScanDataCfg(const scanDataCfg &cfg)

Set scan data configuration. Set format of scan message returned by device.

Parameters:

cfg – structure containing scan data configuration.

scanOutputRange getScanOutputRange() const

Get current output range configuration. Get output range configuration :

  • scanning resolution.

  • start angle.

  • stop angle.

Returns:

scanOutputRange structure.

void scanContinous(int start)

Start or stop continuous data acquisition. After reception of this command device start or stop continuous data stream containing scan messages.

Parameters:

start – 1 : start 0 : stop

bool getScanData(scanData *scan_data)

Receive single scan message.

Returns:

true if scan was read successfully, false if error or timeout. False implies that higher level logic should take correct action such as reopening the connection.

void saveConfig()

Save data permanently. Parameters are saved in the EEPROM of the LMS and will also be available after the device is switched off and on again.

void startDevice()

The device is returned to the measurement mode after configuration.

Protected Attributes

bool connected_
rclcpp::Logger logger_
LMSBuffer buffer_
int socket_fd_

Protected Static Functions

static void parseScanData(char *buf, scanData *data)

Receive single scan message.

Parameters:

data – pointer to scanData buffer structure.