Go to the documentation of this file.
199 void connect(std::string host,
int port = 2111);
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
int dist_len1
Number of samples in dist1.
int stopAngle
Stop angle. 1/10000 degree.
uint16_t rssi1[1082]
Remission values for the first reflected pulse.
bool deviceName
Device name. Determines whether the device name is to be output.
void startDevice()
The device is returned to the measurement mode after configuration.
struct _scanData scanData
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring.
int outputChannel
Output channels. Defines which output channel is activated.
int dist_len2
Number of samples in dist2.
void saveConfig()
Save data permanently. Parameters are saved in the EEPROM of the LMS and will also be available after...
int rssi_len1
Number of samples in rssi1.
status_t queryStatus()
Get current status of LMS1xx device.
uint16_t dist1[1082]
Radial distance for the first reflected pulse.
Structure containing scan configuration.
struct _scanDataCfg scanDataCfg
void setScanCfg(const scanCfg &cfg)
Set scan configuration. Get scan configuration :
void disconnect()
Disconnect from LMS1xx device.
int resolution
Remission resolution. Defines whether the remission values are output with 8-bit or 16bit resolution.
uint16_t rssi2[1082]
Remission values for the second reflected pulse.
bool position
Position. Defines whether position values are output.
bool isConnected()
Get status of connection.
void startMeas()
Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring.
int outputInterval
Output interval. Defines which scan is output.
int scaningFrequency
Scanning frequency. 1/100 Hz.
uint16_t dist2[1082]
Radial distance for the second reflected pulse.
Class responsible for communicating with LMS1xx device.
int encoder
Encoders channels. Defines which output channel is activated.
bool remission
Remission. Defines whether remission values are output.
int rssi_len2
Number of samples in rssi2.
bool getData(scanData &data)
Receive single scan message.
int startAngle
Start angle. 1/10000 degree.
int angleResolution
Scanning resolution. 1/10000 degree.
Structure containing single scan message.
Structure containing scan data configuration.
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 :
void scanContinous(int start)
Start or stop continuous data acquisition. After reception of this command device start or stop conti...
void connect(std::string host, int port=2111)
Connect to LMS1xx.
cob_sick_lms1xx
Author(s): Konrad Banachowicz
autogenerated on Wed Nov 8 2023 03:47:47