31 std::cout <<
"connection failend" << std::endl;
35 std::cout <<
"Connected to laser" << std::endl;
37 std::cout <<
"Loging in ..." << std::endl;
42 std::cout <<
"Geting scan configuration ..." << ::std::endl;
47 c.angleResolution = 5000;
48 c.scaningFrequency = 5000;
53 cc.deviceName =
false;
59 cc.outputInterval = 1;
64 std::cout <<
"Start measurements ..." << std::endl;
67 std::cout <<
"Wait for ready status ..." << std::endl;
72 std::cout <<
"status : " << ret << std::endl;
75 std::cout <<
"Laser ready" << std::endl;
77 std::cout <<
"Start continuous data transmission ..." << std::endl;
80 for(
int i =0; i < 3; i++)
82 std::cout <<
"Receive data sample ..." << std::endl;
86 std::cout <<
"Stop continuous data transmission ..." << std::endl;
91 std::cout <<
"Disconnect from laser" << std::endl;
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.
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring...
Structure containing single scan message.
Structure containing scan configuration.
void setScanCfg(const scanCfg &cfg)
Set 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 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.
bool getData(scanData &data)
Receive single scan message.
Structure containing scan data configuration.
Class responsible for communicating with LMS1xx device.