lms1xx.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef LMS1XX_H_
19 #define LMS1XX_H_
20 
21 #include <string>
22 #include <stdint.h>
23 
30 typedef struct _scanCfg {
36 
42 
48 
53  int stopAngle;
54 } scanCfg;
55 
62 typedef struct _scanDataCfg {
63 
69 
74  bool remission;
75 
81 
86  int encoder;
87 
92  bool position;
93 
98  bool deviceName;
99 
100  bool timestamp;
101 
112 } scanDataCfg;
113 
120 typedef struct _scanData {
121 
127 
132  uint16_t dist1[1082];
133 
139 
144  uint16_t dist2[1082];
145 
151 
156  uint16_t rssi1[1082];
157 
163 
168  uint16_t rssi2[1082];
169 } scanData;
170 
171 typedef enum {
175  idle = 3,
176  rotated = 4,
178  ready = 6,
180 } status_t;
181 
189 class LMS1xx {
190 public:
191  LMS1xx();
192  virtual ~LMS1xx();
193 
199  void connect(std::string host, int port = 2111);
200 
204  void disconnect();
205 
210  bool isConnected();
211 
216  void startMeas();
217 
222  void stopMeas();
223 
229 
234  void login();
235 
245  scanCfg getScanCfg() const;
246 
256  void setScanCfg(const scanCfg &cfg);
257 
263  void setScanDataCfg(const scanDataCfg &cfg);
264 
270  void scanContinous(int start);
271 
277  bool getData(scanData& data);
278 
284  void saveConfig();
285 
290  void startDevice();
291 
292 private:
293  bool connected;
294  bool debug;
295 
296  int sockDesc;
297 };
298 
299 #endif /* LMS1XX_H_ */
LMS1xx::login
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
Definition: lms1xx.cpp:119
_scanData::dist_len1
int dist_len1
Number of samples in dist1.
Definition: lms1xx.h:126
_scanCfg::stopAngle
int stopAngle
Stop angle. 1/10000 degree.
Definition: lms1xx.h:53
ready_for_measurement
@ ready_for_measurement
Definition: lms1xx.h:179
_scanData::rssi1
uint16_t rssi1[1082]
Remission values for the first reflected pulse.
Definition: lms1xx.h:156
_scanCfg
Definition: lms1xx.h:30
_scanDataCfg::deviceName
bool deviceName
Device name. Determines whether the device name is to be output.
Definition: lms1xx.h:98
LMS1xx::startDevice
void startDevice()
The device is returned to the measurement mode after configuration.
Definition: lms1xx.cpp:456
scanData
struct _scanData scanData
LMS1xx::stopMeas
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring.
Definition: lms1xx.cpp:85
LMS1xx::~LMS1xx
virtual ~LMS1xx()
Definition: lms1xx.cpp:36
status_t
status_t
Definition: lms1xx.h:171
_scanDataCfg::outputChannel
int outputChannel
Output channels. Defines which output channel is activated.
Definition: lms1xx.h:68
LMS1xx::sockDesc
int sockDesc
Definition: lms1xx.h:296
_scanData::dist_len2
int dist_len2
Number of samples in dist2.
Definition: lms1xx.h:138
LMS1xx::saveConfig
void saveConfig()
Save data permanently. Parameters are saved in the EEPROM of the LMS and will also be available after...
Definition: lms1xx.cpp:441
_scanData::rssi_len1
int rssi_len1
Number of samples in rssi1.
Definition: lms1xx.h:150
LMS1xx::queryStatus
status_t queryStatus()
Get current status of LMS1xx device.
Definition: lms1xx.cpp:100
_scanData::dist1
uint16_t dist1[1082]
Radial distance for the first reflected pulse.
Definition: lms1xx.h:132
scanCfg
Structure containing scan configuration.
scanDataCfg
struct _scanDataCfg scanDataCfg
LMS1xx::setScanCfg
void setScanCfg(const scanCfg &cfg)
Set scan configuration. Get scan configuration :
Definition: lms1xx.cpp:154
rotated
@ rotated
Definition: lms1xx.h:176
LMS1xx::disconnect
void disconnect()
Disconnect from LMS1xx device.
Definition: lms1xx.cpp:59
_scanDataCfg::resolution
int resolution
Remission resolution. Defines whether the remission values are output with 8-bit or 16bit resolution.
Definition: lms1xx.h:80
_scanData::rssi2
uint16_t rssi2[1082]
Remission values for the second reflected pulse.
Definition: lms1xx.h:168
in_preparation
@ in_preparation
Definition: lms1xx.h:177
_scanDataCfg::position
bool position
Position. Defines whether position values are output.
Definition: lms1xx.h:92
LMS1xx::isConnected
bool isConnected()
Get status of connection.
Definition: lms1xx.cpp:66
LMS1xx::startMeas
void startMeas()
Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring.
Definition: lms1xx.cpp:70
_scanDataCfg::outputInterval
int outputInterval
Output interval. Defines which scan is output.
Definition: lms1xx.h:111
undefined
@ undefined
Definition: lms1xx.h:172
idle
@ idle
Definition: lms1xx.h:175
_scanCfg::scaningFrequency
int scaningFrequency
Scanning frequency. 1/100 Hz.
Definition: lms1xx.h:35
LMS1xx::debug
bool debug
Definition: lms1xx.h:294
_scanData::dist2
uint16_t dist2[1082]
Radial distance for the second reflected pulse.
Definition: lms1xx.h:144
LMS1xx::LMS1xx
LMS1xx()
Definition: lms1xx.cpp:31
LMS1xx
Class responsible for communicating with LMS1xx device.
Definition: lms1xx.h:189
start
ROSCPP_DECL void start()
initialisation
@ initialisation
Definition: lms1xx.h:173
_scanDataCfg::encoder
int encoder
Encoders channels. Defines which output channel is activated.
Definition: lms1xx.h:86
LMS1xx::connected
bool connected
Definition: lms1xx.h:293
_scanDataCfg::remission
bool remission
Remission. Defines whether remission values are output.
Definition: lms1xx.h:74
_scanData::rssi_len2
int rssi_len2
Number of samples in rssi2.
Definition: lms1xx.h:162
_scanDataCfg
Definition: lms1xx.h:62
LMS1xx::getData
bool getData(scanData &data)
Receive single scan message.
Definition: lms1xx.cpp:203
_scanCfg::startAngle
int startAngle
Start angle. 1/10000 degree.
Definition: lms1xx.h:47
scanCfg
struct _scanCfg scanCfg
_scanCfg::angleResolution
int angleResolution
Scanning resolution. 1/10000 degree.
Definition: lms1xx.h:41
_scanDataCfg::timestamp
bool timestamp
Definition: lms1xx.h:100
scanData
Structure containing single scan message.
scanDataCfg
Structure containing scan data configuration.
_scanData
Definition: lms1xx.h:120
LMS1xx::setScanDataCfg
void setScanDataCfg(const scanDataCfg &cfg)
Set scan data configuration. Set format of scan message returned by device.
Definition: lms1xx.cpp:167
configuration
@ configuration
Definition: lms1xx.h:174
LMS1xx::getScanCfg
scanCfg getScanCfg() const
Get current scan configuration. Get scan configuration :
Definition: lms1xx.cpp:134
ready
@ ready
Definition: lms1xx.h:178
LMS1xx::scanContinous
void scanContinous(int start)
Start or stop continuous data acquisition. After reception of this command device start or stop conti...
Definition: lms1xx.cpp:181
LMS1xx::connect
void connect(std::string host, int port=2111)
Connect to LMS1xx.
Definition: lms1xx.cpp:40


cob_sick_lms1xx
Author(s): Konrad Banachowicz
autogenerated on Wed Nov 8 2023 03:47:47