LMS1xx.h
Go to the documentation of this file.
1 /*
2  * LMS1xx.h
3  *
4  * Created on: 09-08-2010
5  * Author: Konrad Banachowicz
6  ***************************************************************************
7  * This library is free software; you can redistribute it and/or *
8  * modify it under the terms of the GNU Lesser General Public *
9  * License as published by the Free Software Foundation; either *
10  * version 2.1 of the License, or (at your option) any later version. *
11  * *
12  * This library is distributed in the hope that it will be useful, *
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU *
15  * Lesser General Public License for more details. *
16  * *
17  * You should have received a copy of the GNU Lesser General Public *
18  * License along with this library; if not, write to the Free Software *
19  * Foundation, Inc., 59 Temple Place, *
20  * Suite 330, Boston, MA 02111-1307 USA *
21  * *
22  ***************************************************************************/
23 
24 #ifndef LMS1XX_H_
25 #define LMS1XX_H_
26 
27 #include <LMS1xx/lms_buffer.h>
28 #include <LMS1xx/lms_structs.h>
29 #include <string>
30 #include <stdint.h>
31 
32 typedef enum
33 {
34  undefined = 0,
37  idle = 3,
38  rotated = 4,
40  ready = 6,
42 } status_t;
43 
51 class LMS1xx
52 {
53 public:
54  LMS1xx();
55  virtual ~LMS1xx();
56 
62  void connect(std::string host, int port = 2111);
63 
67  void disconnect();
68 
73  bool isConnected();
74 
79  void startMeas();
80 
85  void stopMeas();
86 
92 
97  void login();
98 
108  scanCfg getScanCfg() const;
109 
119  void setScanCfg(const scanCfg &cfg);
120 
126  void setScanDataCfg(const scanDataCfg &cfg);
127 
137 
143  void scanContinous(int start);
144 
150  bool getScanData(scanData* scan_data);
151 
157  void saveConfig();
158 
163  void startDevice();
164 
165 protected:
170  static void parseScanData(char* buf, scanData* data);
171 
175 };
176 
177 #endif /* LMS1XX_H_ */
178 
Definition: LMS1xx.h:38
Structure containing single scan message.
Definition: lms_structs.h:154
ROSCPP_DECL void start()
void setScanDataCfg(const scanDataCfg &cfg)
Set scan data configuration. Set format of scan message returned by device.
Definition: LMS1xx.cpp:197
scanCfg getScanCfg() const
Get current scan configuration. Get scan configuration :
Definition: LMS1xx.cpp:164
Definition: LMS1xx.h:37
status_t queryStatus()
Get current status of LMS1xx device.
Definition: LMS1xx.cpp:114
scanOutputRange getScanOutputRange() const
Get current output range configuration. Get output range configuration :
Definition: LMS1xx.cpp:211
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
Definition: LMS1xx.cpp:133
Structure containing scan data configuration.
Definition: lms_structs.h:68
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring...
Definition: LMS1xx.cpp:100
void setScanCfg(const scanCfg &cfg)
Set scan configuration. Get scan configuration :
Definition: LMS1xx.cpp:183
Structure containing scan configuration.
Definition: lms_structs.h:35
bool getScanData(scanData *scan_data)
Receive single scan message.
Definition: LMS1xx.cpp:242
void startDevice()
The device is returned to the measurement mode after configuration.
Definition: LMS1xx.cpp:485
void scanContinous(int start)
Start or stop continuous data acquisition. After reception of this command device start or stop conti...
Definition: LMS1xx.cpp:226
LMSBuffer buffer_
Definition: LMS1xx.h:173
void startMeas()
Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring...
Definition: LMS1xx.cpp:86
bool isConnected()
Get status of connection.
Definition: LMS1xx.cpp:81
void disconnect()
Disconnect from LMS1xx device.
Definition: LMS1xx.cpp:72
void connect(std::string host, int port=2111)
Connect to LMS1xx.
Definition: LMS1xx.cpp:47
Definition: LMS1xx.h:40
int socket_fd_
Definition: LMS1xx.h:174
LMS1xx()
Definition: LMS1xx.cpp:39
void saveConfig()
Save data permanently. Parameters are saved in the EEPROM of the LMS and will also be available after...
Definition: LMS1xx.cpp:470
Class responsible for communicating with LMS1xx device.
Definition: LMS1xx.h:51
virtual ~LMS1xx()
Definition: LMS1xx.cpp:43
status_t
Definition: LMS1xx.h:32
static void parseScanData(char *buf, scanData *data)
Receive single scan message.
Definition: LMS1xx.cpp:284
bool connected_
Definition: LMS1xx.h:172


lms1xx
Author(s): Konrad Banachowicz
autogenerated on Wed Jan 22 2020 03:36:59