62 void connect(std::string host,
int port = 2111);
Structure containing single scan message.
void setScanDataCfg(const scanDataCfg &cfg)
Set scan data configuration. Set format of scan message returned by device.
scanCfg getScanCfg() const
Get current scan configuration. Get scan configuration :
status_t queryStatus()
Get current status of LMS1xx device.
scanOutputRange getScanOutputRange() const
Get current output range configuration. Get output range configuration :
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
Structure containing scan data configuration.
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring...
void setScanCfg(const scanCfg &cfg)
Set scan configuration. Get scan configuration :
Structure containing scan configuration.
bool getScanData(scanData *scan_data)
Receive single scan message.
void startDevice()
The device is returned to the measurement mode after configuration.
void scanContinous(int start)
Start or stop continuous data acquisition. After reception of this command device start or stop conti...
void startMeas()
Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring...
bool isConnected()
Get status of connection.
void disconnect()
Disconnect from LMS1xx device.
void connect(std::string host, int port=2111)
Connect to LMS1xx.
void saveConfig()
Save data permanently. Parameters are saved in the EEPROM of the LMS and will also be available after...
Class responsible for communicating with LMS1xx device.
static void parseScanData(char *buf, scanData *data)
Receive single scan message.