forked from konradb3/libLMS1xx
-
Notifications
You must be signed in to change notification settings - Fork 1
/
LMS1xx.cpp
399 lines (340 loc) · 10.2 KB
/
LMS1xx.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
/*
* LMS1xx.cpp
*
* Created on: 09-08-2010
* Author: Konrad Banachowicz
***************************************************************************
* This library is free software; you can redistribute it and/or *
* modify it under the terms of the GNU Lesser General Public *
* License as published by the Free Software Foundation; either *
* version 2.1 of the License, or (at your option) any later version. *
* *
* This library is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU *
* Lesser General Public License for more details. *
* *
* You should have received a copy of the GNU Lesser General Public *
* License along with this library; if not, write to the Free Software *
* Foundation, Inc., 59 Temple Place, *
* Suite 330, Boston, MA 02111-1307 USA *
* *
***************************************************************************/
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <cstdio>
#include <cstdlib>
#include <cstring>
#include <unistd.h>
#include "LMS1xx.h"
LMS1xx::LMS1xx() :
connected(false) {
debug = false;
}
LMS1xx::~LMS1xx() {
}
void LMS1xx::connect(std::string host, int port) {
if (!connected) {
sockDesc = socket(PF_INET, SOCK_STREAM, IPPROTO_TCP);
if (sockDesc) {
struct sockaddr_in stSockAddr;
int Res;
stSockAddr.sin_family = PF_INET;
stSockAddr.sin_port = htons(port);
Res = inet_pton(AF_INET, host.c_str(), &stSockAddr.sin_addr);
int ret = ::connect(sockDesc, (struct sockaddr *) &stSockAddr,
sizeof stSockAddr);
if (ret == 0) {
connected = true;
}
}
}
}
void LMS1xx::disconnect() {
if (connected) {
close(sockDesc);
connected = false;
}
}
bool LMS1xx::isConnected() {
return connected;
}
void LMS1xx::startMeas() {
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sMN LMCstartmeas", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
}
void LMS1xx::stopMeas() {
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sMN LMCstopmeas", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
}
status_t LMS1xx::queryStatus() {
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sRN STlms", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
int ret;
sscanf((buf + 10), "%d", &ret);
return (status_t) ret;
}
void LMS1xx::login() {
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sMN SetAccessMode 03 F4724744", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
}
scanCfg LMS1xx::getScanCfg() const {
scanCfg cfg;
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sRN LMPscancfg", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
sscanf(buf + 1, "%*s %*s %X %*d %X %X %X", &cfg.scaningFrequency,
&cfg.angleResolution, &cfg.startAngle, &cfg.stopAngle);
return cfg;
}
void LMS1xx::setScanCfg(const scanCfg &cfg) {
char buf[100];
sprintf(buf, "%c%s %X +1 %X %X %X%c", 0x02, "sMN mLMPsetscancfg",
cfg.scaningFrequency, cfg.angleResolution, cfg.startAngle,
cfg.stopAngle, 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
buf[len - 1] = 0;
}
void LMS1xx::setScanDataCfg(const scanDataCfg &cfg) {
char buf[100];
sprintf(buf, "%c%s %02X 00 %d %d 0 %02X 00 %d %d 0 %d +%d%c", 0x02,
"sWN LMDscandatacfg", cfg.outputChannel, cfg.remission ? 1 : 0,
cfg.resolution, cfg.encoder, cfg.position ? 1 : 0,
cfg.deviceName ? 1 : 0, cfg.timestamp ? 1 : 0, cfg.outputInterval, 0x03);
if(debug)
printf("%s\n", buf);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
buf[len - 1] = 0;
}
void LMS1xx::scanContinous(int start) {
char buf[100];
sprintf(buf, "%c%s %d%c", 0x02, "sEN LMDscandata", start, 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
if (buf[0] != 0x02)
printf("invalid packet recieved\n");
if (debug) {
buf[len] = 0;
printf("%s\n", buf);
}
if (start = 0) {
for (int i = 0; i < 10; i++)
read(sockDesc, buf, 100);
}
}
void LMS1xx::getData(scanData& data) {
char buf[20000];
fd_set rfds;
struct timeval tv;
int retval, len;
len = 0;
do {
FD_ZERO(&rfds);
FD_SET(sockDesc, &rfds);
tv.tv_sec = 0;
tv.tv_usec = 50000;
retval = select(sockDesc + 1, &rfds, NULL, NULL, &tv);
if (retval) {
len += read(sockDesc, buf + len, 20000 - len);
}
} while ((buf[0] != 0x02) || (buf[len - 1] != 0x03));
// if (debug)
// std::cout << "scan data recieved" << std::endl;
buf[len - 1] = 0;
char* tok = strtok(buf, " "); //Type of command
tok = strtok(NULL, " "); //Command
tok = strtok(NULL, " "); //VersionNumber
tok = strtok(NULL, " "); //DeviceNumber
tok = strtok(NULL, " "); //Serial number
tok = strtok(NULL, " "); //DeviceStatus
tok = strtok(NULL, " "); //MessageCounter
tok = strtok(NULL, " "); //ScanCounter
tok = strtok(NULL, " "); //PowerUpDuration
tok = strtok(NULL, " "); //TransmissionDuration
tok = strtok(NULL, " "); //InputStatus
tok = strtok(NULL, " "); //OutputStatus
tok = strtok(NULL, " "); //ReservedByteA
tok = strtok(NULL, " "); //ScanningFrequency
tok = strtok(NULL, " "); //MeasurementFrequency
tok = strtok(NULL, " ");
tok = strtok(NULL, " ");
tok = strtok(NULL, " ");
tok = strtok(NULL, " "); //NumberEncoders
int NumberEncoders;
sscanf(tok, "%d", &NumberEncoders);
for (int i = 0; i < NumberEncoders; i++) {
tok = strtok(NULL, " "); //EncoderPosition
tok = strtok(NULL, " "); //EncoderSpeed
}
tok = strtok(NULL, " "); //NumberChannels16Bit
int NumberChannels16Bit;
sscanf(tok, "%d", &NumberChannels16Bit);
if (debug)
printf("NumberChannels16Bit : %d\n", NumberChannels16Bit);
for (int i = 0; i < NumberChannels16Bit; i++) {
int type = -1; // 0 DIST1 1 DIST2 2 RSSI1 3 RSSI2
char content[6];
tok = strtok(NULL, " "); //MeasuredDataContent
sscanf(tok, "%s", content);
if (!strcmp(content, "DIST1")) {
type = 0;
} else if (!strcmp(content, "DIST2")) {
type = 1;
} else if (!strcmp(content, "RSSI1")) {
type = 2;
} else if (!strcmp(content, "RSSI2")) {
type = 3;
}
tok = strtok(NULL, " "); //ScalingFactor
tok = strtok(NULL, " "); //ScalingOffset
tok = strtok(NULL, " "); //Starting angle
tok = strtok(NULL, " "); //Angular step width
tok = strtok(NULL, " "); //NumberData
int NumberData;
sscanf(tok, "%X", &NumberData);
if (debug)
printf("NumberData : %d\n", NumberData);
if (type == 0) {
data.dist_len1 = NumberData;
} else if (type == 1) {
data.dist_len2 = NumberData;
} else if (type == 2) {
data.rssi_len1 = NumberData;
} else if (type == 3) {
data.rssi_len2 = NumberData;
}
for (int i = 0; i < NumberData; i++) {
int dat;
tok = strtok(NULL, " "); //data
sscanf(tok, "%X", &dat);
if (type == 0) {
data.dist1[i] = dat;
} else if (type == 1) {
data.dist2[i] = dat;
} else if (type == 2) {
data.rssi1[i] = dat;
} else if (type == 3) {
data.rssi2[i] = dat;
}
}
}
tok = strtok(NULL, " "); //NumberChannels8Bit
int NumberChannels8Bit;
sscanf(tok, "%d", &NumberChannels8Bit);
if (debug)
printf("NumberChannels8Bit : %d\n", NumberChannels8Bit);
for (int i = 0; i < NumberChannels8Bit; i++) {
int type = -1;
char content[6];
tok = strtok(NULL, " "); //MeasuredDataContent
sscanf(tok, "%s", content);
if (!strcmp(content, "DIST1")) {
type = 0;
} else if (!strcmp(content, "DIST2")) {
type = 1;
} else if (!strcmp(content, "RSSI1")) {
type = 2;
} else if (!strcmp(content, "RSSI2")) {
type = 3;
}
tok = strtok(NULL, " "); //ScalingFactor
tok = strtok(NULL, " "); //ScalingOffset
tok = strtok(NULL, " "); //Starting angle
tok = strtok(NULL, " "); //Angular step width
tok = strtok(NULL, " "); //NumberData
int NumberData;
sscanf(tok, "%X", &NumberData);
if (debug)
printf("NumberData : %d\n", NumberData);
if (type == 0) {
data.dist_len1 = NumberData;
} else if (type == 1) {
data.dist_len2 = NumberData;
} else if (type == 2) {
data.rssi_len1 = NumberData;
} else if (type == 3) {
data.rssi_len2 = NumberData;
}
for (int i = 0; i < NumberData; i++) {
int dat;
tok = strtok(NULL, " "); //data
sscanf(tok, "%X", &dat);
if (type == 0) {
data.dist1[i] = dat;
} else if (type == 1) {
data.dist2[i] = dat;
} else if (type == 2) {
data.rssi1[i] = dat;
} else if (type == 3) {
data.rssi2[i] = dat;
}
}
}
}
void LMS1xx::saveConfig() {
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sMN mEEwriteall", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
}
void LMS1xx::startDevice() {
char buf[100];
sprintf(buf, "%c%s%c", 0x02, "sMN Run", 0x03);
write(sockDesc, buf, strlen(buf));
int len = read(sockDesc, buf, 100);
// if (buf[0] != 0x02)
// std::cout << "invalid packet recieved" << std::endl;
// if (debug) {
// buf[len] = 0;
// std::cout << buf << std::endl;
// }
}