forked from SICKAG/sick_scan
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsick_scan_common.cpp
3033 lines (2628 loc) · 92 KB
/
sick_scan_common.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
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/**
* \file
* \brief Laser Scanner communication main routine
*
* Copyright (C) 2013, Osnabrück University
* Copyright (C) 2017, Ing.-Buero Dr. Michael Lehning, Hildesheim
* Copyright (C) 2017, SICK AG, Waldkirch
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of Osnabrück University nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
* * Neither the name of SICK AG nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission
* * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* Last modified: 28th May 2018
*
* Authors:
* Michael Lehning <michael.lehning@lehning.de>
* Jochen Sprickerhof <jochen@sprickerhof.de>
* Martin Günther <mguenthe@uos.de>
*
* Based on the TiM communication example by SICK AG.
*
*/
#ifdef _MSC_VER // compiling simulation for MS-Visual C++ - not defined for linux system
#pragma warning(disable: 4996)
#pragma warning(disable: 4267) // due to conversion warning size_t in the ros header file
#define _WIN32_WINNT 0x0501
#endif
#include <sick_scan/sick_scan_common_nw.h>
#include <sick_scan/sick_scan_common.h>
#include <sick_scan/sick_generic_radar.h>
#ifdef _MSC_VER
#include "sick_scan/rosconsole_simu.hpp"
#endif
#include "sick_scan/binScanf.hpp"
// if there is a missing RadarScan.h, try to run catkin_make in der workspace-root
#include <sick_scan/RadarScan.h>
#include <cstdio>
#include <cstring>
#define _USE_MATH_DEFINES
#include <math.h>
#ifndef rad2deg
#define rad2deg(x) ((x) / M_PI * 180.0)
#endif
#define deg2rad_const (0.017453292519943295769236907684886f)
#include "sick_scan/tcp/colaa.hpp"
#include "sick_scan/tcp/colab.hpp"
#include <map>
#include <climits>
/*!
\brief Universal swapping function
\param ptr: Pointer to datablock
\param numBytes : size of variable in bytes
*/
void swap_endian(unsigned char *ptr, int numBytes)
{
unsigned char *buf = (ptr);
unsigned char tmpChar;
for (int i = 0; i < numBytes / 2; i++)
{
tmpChar = buf[numBytes - 1 - i];
buf[numBytes - 1 - i] = buf[i];
buf[i] = tmpChar;
}
}
/*!
\brief return diagnostic error code (small helper function)
This small helper function was introduced to allow the compiling under Visual c++.
\return Diagnostic error code (value 2)
*/
static int getDiagnosticErrorCode() // workaround due to compiling error under Visual C++
{
#ifdef _MSC_VER
#undef ERROR
return(2);
#else
return(diagnostic_msgs::DiagnosticStatus::ERROR);
#endif
}
/*!
\brief Convert part of unsigned char vector into a std::string
\param replyDummy: Pointer to byte block hold in vector
\param off: Starting Position for copy command
\param len: Number of bytes which should be copied
\return result of copy action as std::string
*/
const std::string binScanfGetStringFromVec(std::vector<unsigned char>* replyDummy, int off, long len)
{
std::string s;
s = "";
for (int i = 0; i < len; i++)
{
char ch = (char)((*replyDummy)[i + off]);
s += ch;
}
return(s);
}
namespace sick_scan
{
/*!
\brief calculate crc-code for last byte of binary message
XOR-calucation is done ONLY over message content (i.e. skipping the first 8 Bytes holding 0x02020202 <Length Information as 4-byte long>)
\param msgBlock: message content
\param len: Length of message content in byte
\return XOR-calucation abount message content (msgBlock[0] ^ msgBlock[1] .... msgBlock[len-1]
*/
unsigned char sick_crc8(unsigned char *msgBlock, int len)
{
unsigned char xorVal = 0x00;
int off = 0;
for (int i = off; i < len; i++)
{
unsigned char val = msgBlock[i];
xorVal ^= val;
}
return(xorVal);
}
/*!
\brief Converts a SOPAS command to a human readable string
\param s: ASCII-Sopas command including 0x02 and 0x03
\return Human readable string 0x02 and 0x02 are converted to "<STX>" and "<ETX>"
*/
std::string stripControl(std::string s)
{
std::string dest;
for (int i = 0; i < s.length(); i++)
{
if (s[i] >= ' ')
{
dest += s[i];
}
else
{
switch (s[i])
{
case 0x02: dest += "<STX>"; break;
case 0x03: dest += "<ETX>"; break;
}
}
}
return(dest);
}
/*!
\brief Construction of SickScanCommon
\param parser: Corresponding parser holding specific scanner parameter
*/
SickScanCommon::SickScanCommon(SickGenericParser* parser) :
diagnosticPub_(NULL), parser_(parser)
// FIXME All Tims have 15Hz
{
expectedFrequency_ = this->parser_->getCurrentParamPtr()->getExpectedFrequency();
setSensorIsRadar(false);
init_cmdTables();
#ifndef _MSC_VER
dynamic_reconfigure::Server<sick_scan::SickScanConfig>::CallbackType f;
f = boost::bind(&sick_scan::SickScanCommon::update_config, this, _1, _2);
dynamic_reconfigure_server_.setCallback(f);
#else
// For simulation under MS Visual c++ the update config is switched off
{
SickScanConfig cfg;
ros::NodeHandle tmp("~");
double min_angle, max_angle, res_angle;
tmp.getParam(PARAM_MIN_ANG, min_angle);
tmp.getParam(PARAM_MAX_ANG, max_angle);
tmp.getParam(PARAM_RES_ANG, res_angle);
cfg.min_ang = min_angle;
cfg.max_ang = max_angle;
cfg.skip = 0;
update_config(cfg);
}
#endif
// datagram publisher (only for debug)
ros::NodeHandle pn("~");
pn.param<bool>("publish_datagram", publish_datagram_, false);
if (publish_datagram_)
datagram_pub_ = nh_.advertise<std_msgs::String>("datagram", 1000);
// Pointcloud2 publisher
//
cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud", 100);
// just for debugging, but very helpful for the start
cloud_radar_rawtarget_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud_radar_rawtarget", 100);
cloud_radar_track_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("cloud_radar_track", 100);
radarScan_pub_ = nh_.advertise<sick_scan::RadarScan>("radar", 100);
// scan publisher
pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan", 1000);
#ifndef _MSC_VER
diagnostics_.setHardwareID("none"); // set from device after connection
diagnosticPub_ = new diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan>(pub_, diagnostics_,
// frequency should be target +- 10%.
diagnostic_updater::FrequencyStatusParam(&expectedFrequency_, &expectedFrequency_, 0.1, 10),
// timestamp delta can be from 0.0 to 1.3x what it ideally is.
diagnostic_updater::TimeStampStatusParam(-1, 1.3 * 1.0 / expectedFrequency_ - config_.time_offset));
ROS_ASSERT(diagnosticPub_ != NULL);
#endif
}
/*!
\brief Stops sending scan data
\return error code
*/
int SickScanCommon::stop_scanner()
{
/*
* Stop streaming measurements
*/
const char requestScanData0[] = { "\x02sEN LMDscandata 0\x03\0" };
int result = sendSOPASCommand(requestScanData0, NULL);
if (result != 0)
// use printf because we cannot use ROS_ERROR from the destructor
printf("\nSOPAS - Error stopping streaming scan data!\n");
else
printf("\nSOPAS - Stopped streaming scan data.\n");
return result;
}
/*!
\brief Convert little endian to big endian (should be replaced by swap-routine)
\param *vecArr Pointer to 4 byte block
\return swapped 4-byte-value as long
*/
unsigned long SickScanCommon::convertBigEndianCharArrayToUnsignedLong(const unsigned char *vecArr)
{
unsigned long val = 0;
for (int i = 0; i < 4; i++)
{
val = val << 8;
val |= vecArr[i];
}
return(val);
}
/*!
\brief Check block for correct framing and starting sequence of a binary message
\param reply Pointer to datablock
\return length of message (-1 if message format is not correct)
*/
int sick_scan::SickScanCommon::checkForBinaryAnswer(const std::vector<unsigned char>* reply)
{
int retVal = -1;
if (reply == NULL)
{
}
else
{
if (reply->size() < 8)
{
retVal = -1;
}
else
{
const unsigned char *ptr = &((*reply)[0]);
unsigned binId = convertBigEndianCharArrayToUnsignedLong(ptr);
unsigned cmdLen = convertBigEndianCharArrayToUnsignedLong(ptr + 4);
if (binId == 0x02020202)
{
int replyLen = reply->size();
if (replyLen == 8 + cmdLen + 1)
{
retVal = cmdLen;
}
}
}
}
return(retVal);
}
/*!
\brief Reboot scanner (todo: this does not work if the scanner is set to binary mode) Fix me!
\return Result of rebooting attempt
*/
bool SickScanCommon::rebootScanner()
{
/*
* Set Maintenance access mode to allow reboot to be sent
*/
std::vector<unsigned char> access_reply;
// changed from "03" to "3"
int result = sendSOPASCommand("\x02sMN SetAccessMode 3 F4724744\x03\0", &access_reply);
if (result != 0)
{
ROS_ERROR("SOPAS - Error setting access mode");
diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error setting access mode.");
return false;
}
std::string access_reply_str = replyToString(access_reply);
if (access_reply_str != "sAN SetAccessMode 1")
{
ROS_ERROR_STREAM("SOPAS - Error setting access mode, unexpected response : " << access_reply_str);
diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error setting access mode.");
return false;
}
/*
* Send reboot command
*/
std::vector<unsigned char> reboot_reply;
result = sendSOPASCommand("\x02sMN mSCreboot\x03\0", &reboot_reply);
if (result != 0)
{
ROS_ERROR("SOPAS - Error rebooting scanner");
diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error rebooting device.");
return false;
}
std::string reboot_reply_str = replyToString(reboot_reply);
if (reboot_reply_str != "sAN mSCreboot")
{
ROS_ERROR_STREAM("SOPAS - Error rebooting scanner, unexpected response : " << reboot_reply_str);
diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error setting access mode.");
return false;
}
ROS_INFO("SOPAS - Rebooted scanner");
// Wait a few seconds after rebooting
ros::Duration(15.0).sleep();
return true;
}
/*!
\brief Destructor of SickScanCommon
*/
SickScanCommon::~SickScanCommon()
{
delete diagnosticPub_;
printf("sick_scan driver exiting.\n");
}
/*!
\brief Generate expected answer string from the command string
\param requestStr command string (either as ASCII or BINARY)
\return expected answer string
*/
std::string SickScanCommon::generateExpectedAnswerString(const std::vector<unsigned char> requestStr)
{
std::string expectedAnswer = "";
int i = 0;
char cntWhiteCharacter = 0;
int initalTokenCnt = 2; // number of initial token to identify command
std::map<std::string, int> specialTokenLen;
char firstToken[1024] = { 0 };
specialTokenLen["sRI"] = 1; // for SRi-Command only the first token identify the command
std::string tmpStr = "";
int cnt0x02 = 0;
bool isBinary = false;
for (int i = 0; i < 4; i++)
{
if (i < requestStr.size())
{
if (requestStr[i] == 0x02)
{
cnt0x02++;
}
}
}
int iStop = requestStr.size(); // copy string until end of string
if (cnt0x02 == 4)
{
int cmdLen = 0;
for (int i = 0; i < 4; i++)
{
cmdLen |= cmdLen << 8;
cmdLen |= requestStr[i + 4];
}
iStop = cmdLen + 8;
isBinary = true;
}
int iStart = (isBinary == true) ? 8 : 0;
for (int i = iStart; i < iStop; i++)
{
tmpStr += (char)requestStr[i];
}
if (isBinary)
{
tmpStr = "\x2" + tmpStr;
}
if (sscanf(tmpStr.c_str(), "\x2%s", firstToken) == 1)
{
if (specialTokenLen.find(firstToken) != specialTokenLen.end())
{
initalTokenCnt = specialTokenLen[firstToken];
}
}
for (int i = iStart; i < iStop; i++)
{
if ((requestStr[i] == ' ') || (requestStr[i] == '\x3'))
{
cntWhiteCharacter++;
}
if (cntWhiteCharacter >= initalTokenCnt)
{
break;
}
if (requestStr[i] == '\x2')
{
}
else
{
expectedAnswer += requestStr[i];
}
}
/*!
* Map that defines expected answer identifiers
*/
std::map<std::string, std::string> keyWordMap;
keyWordMap["sWN"] = "sWA";
keyWordMap["sRN"] = "sRA";
keyWordMap["sRI"] = "sRA";
keyWordMap["sMN"] = "sAN";
keyWordMap["sEN"] = "sEA";
for (std::map<std::string, std::string>::iterator it = keyWordMap.begin(); it != keyWordMap.end(); it++)
{
std::string keyWord = it->first;
std::string newKeyWord = it->second;
size_t pos = expectedAnswer.find(keyWord);
if (pos == std::string::npos)
{
}
else
{
if (pos == 0) // must be 0, if keyword has been found
{
expectedAnswer.replace(pos, keyWord.length(), newKeyWord);
}
else
{
ROS_WARN("Unexpected position of key identifier.\n");
}
}
}
return(expectedAnswer);
}
/*!
\brief send command and check answer
\param requestStr: Sopas-Command
\param *reply: Antwort-String
\param cmdId: Command index to derive the correct error message (optional)
\return error code
*/
int SickScanCommon::sendSopasAndCheckAnswer(std::string requestStr, std::vector<unsigned char> *reply, int cmdId = -1)
{
std::vector<unsigned char> requestStringVec;
for (int i = 0; i < requestStr.length(); i++)
{
requestStringVec.push_back(requestStr[i]);
}
int retCode = sendSopasAndCheckAnswer(requestStringVec, reply, cmdId);
return(retCode);
}
/*!
\brief send command and check answer
\param requestStr: Sopas-Command given as byte-vector
\param *reply: Antwort-String
\param cmdId: Command index to derive the correct error message (optional)
\return error code
*/
int SickScanCommon::sendSopasAndCheckAnswer(std::vector<unsigned char> requestStr, std::vector<unsigned char> *reply, int cmdId = -1)
{
std::string cmdStr = "";
int cmdLen = 0;
for (int i = 0; i < requestStr.size(); i++)
{
cmdLen++;
cmdStr += (char)requestStr[i];
}
int result = -1;
std::string errString;
if (cmdId == -1)
{
errString = "Error unexpected Sopas Answer for request " + stripControl(cmdStr);
}
else
{
errString = this->sopasCmdErrMsg[cmdId];
}
std::string expectedAnswer = generateExpectedAnswerString(requestStr);
// send sopas cmd
std::string reqStr = replyToString(requestStr);
ROS_INFO("Sending : %s", stripControl(reqStr).c_str());
result = sendSOPASCommand(cmdStr.c_str(), reply, cmdLen);
std::string replyStr = replyToString(*reply);
replyStr = "<STX>" + replyStr + "<ETX>";
ROS_INFO("Receiving: %s", stripControl(replyStr).c_str());
if (result != 0)
{
std::string tmpStr = "SOPAS Communication -" + errString;
ROS_ERROR("%s\n", tmpStr.c_str());
diagnostics_.broadcast(getDiagnosticErrorCode(), tmpStr);
}
else
{
std::string answerStr = replyToString(*reply);
std::string searchPattern = generateExpectedAnswerString(requestStr);
if (answerStr.find(searchPattern) != std::string::npos)
{
result = 0;
}
else
{
std::string tmpMsg = "Error Sopas answer mismatch " + errString + "Answer= >>>" + answerStr + "<<<";
ROS_ERROR("%s\n", tmpMsg.c_str());
diagnostics_.broadcast(getDiagnosticErrorCode(), tmpMsg);
result = -1;
}
}
return result;
}
/*!
\brief set timeout in milliseconds
\param timeOutInMs in milliseconds
\sa getReadTimeOutInMs
*/
void SickScanCommon::setReadTimeOutInMs(int timeOutInMs)
{
readTimeOutInMs = timeOutInMs;
}
/*!
\brief get timeout in milliseconds
\return timeout in milliseconds
\sa setReadTimeOutInMs
*/
int SickScanCommon::getReadTimeOutInMs()
{
return(readTimeOutInMs);
}
/*!
\brief get protocol type as enum
\return enum type of type SopasProtocol
\sa setProtocolType
*/
int SickScanCommon::getProtocolType(void)
{
return m_protocolId;
}
/*!
\brief set protocol type as enum
\sa getProtocolType
*/
void SickScanCommon::setProtocolType(SopasProtocol cola_dialect_id)
{
m_protocolId = cola_dialect_id;
}
/*!
\brief init routine of scanner
\return exit code
*/
int SickScanCommon::init()
{
int result = init_device();
if (result != 0)
{
ROS_FATAL("Failed to init device: %d", result);
return result;
}
result = init_scanner();
if (result != 0)
{
ROS_ERROR("Failed to init scanner Error Code: %d\nWaiting for timeout...\n"
"If the communication mode set in the scanner memory is different from that used by the driver, the scanner's communication mode is changed.\n"
"This requires a restart of the TCP-IP connection, which can extend the start time by up to 30 seconds. There are two ways to prevent this:\n"
"1. [Recommended] Set the communication mode with the SOPAS ET software to binary and save this setting in the scanner's EEPROM.\n"
"2. Use the parameter \"use_binary_protocol\" to overwrite the default settings of the driver.", result);
}
return result;
}
/*!
\brief init command tables and define startup sequence
\return exit code
*/
int SickScanCommon::init_cmdTables()
{
sopasCmdVec.resize(SickScanCommon::CMD_END);
sopasCmdMaskVec.resize(SickScanCommon::CMD_END); // you for cmd with variable content. sprintf should print into corresponding sopasCmdVec
sopasCmdErrMsg.resize(SickScanCommon::CMD_END); // you for cmd with variable content. sprintf should print into corresponding sopasCmdVec
sopasReplyVec.resize(SickScanCommon::CMD_END);
sopasReplyBinVec.resize(SickScanCommon::CMD_END);
sopasReplyStrVec.resize(SickScanCommon::CMD_END);
std::string unknownStr = "Command or Error message not defined";
for (int i = 0; i < SickScanCommon::CMD_END; i++)
{
sopasCmdVec[i] = unknownStr;
sopasCmdMaskVec[i] = unknownStr; // for cmd with variable content. sprintf should print into corresponding sopasCmdVec
sopasCmdErrMsg[i] = unknownStr;
sopasReplyVec[i] = unknownStr;
sopasReplyStrVec[i] = unknownStr;
}
sopasCmdVec[CMD_DEVICE_IDENT_LEGACY] = "\x02sRI 0\x03\0";
sopasCmdVec[CMD_DEVICE_IDENT] = "\x02sRN DeviceIdent\x03\0";
sopasCmdVec[CMD_SERIAL_NUMBER] = "\x02sRN SerialNumber\x03\0";
sopasCmdVec[CMD_FIRMWARE_VERSION] = "\x02sRN FirmwareVersion\x03\0";
sopasCmdVec[CMD_DEVICE_STATE] = "\x02sRN SCdevicestate\x03\0";
sopasCmdVec[CMD_OPERATION_HOURS] = "\x02sRN ODoprh\x03\0";
sopasCmdVec[CMD_POWER_ON_COUNT] = "\x02sRN ODpwrc\x03\0";
sopasCmdVec[CMD_LOCATION_NAME] = "\x02sRN LocationName\x03\0";
sopasCmdVec[CMD_ACTIVATE_STANDBY] = "\x02sMN LMCstandby\x03";
sopasCmdVec[CMD_SET_ACCESS_MODE_3] = "\x02sMN SetAccessMode 3 F4724744\x03\0";
sopasCmdVec[CMD_GET_OUTPUT_RANGES] = "\x02sRN LMPoutputRange\x03";
sopasCmdVec[CMD_RUN] = "\x02sMN Run\x03\0";
sopasCmdVec[CMD_STOP_SCANDATA] = "\x02sEN LMDscandata 0\x03";
sopasCmdVec[CMD_START_SCANDATA] = "\x02sEN LMDscandata 1\x03";
sopasCmdVec[CMD_START_RADARDATA] = "\x02sEN LMDradardata 1\x03";
/*
* Radar specific commands
*/
sopasCmdVec[CMD_SET_TRANSMIT_RAWTARGETS_ON] = "\x02sWN TransmitTargets 1\x03"; // transmit raw target for radar
sopasCmdVec[CMD_SET_TRANSMIT_RAWTARGETS_OFF] = "\x02sWN TransmitTargets 0\x03"; // do not transmit raw target for radar
sopasCmdVec[CMD_SET_TRANSMIT_OBJECTS_ON] = "\x02sWN TransmitObjects 1\x03"; // transmit objects from radar tracking
sopasCmdVec[CMD_SET_TRANSMIT_OBJECTS_OFF] = "\x02sWN TransmitObjects 0\x03"; // do not transmit objects from radar tracking
sopasCmdVec[CMD_SET_TRACKING_MODE_0] = "\x02sWN TCTrackingMode 0\x03"; // set object tracking mode to BASIC
sopasCmdVec[CMD_SET_TRACKING_MODE_1] = "\x02sWN TCTrackingMode 1\x03"; // set object tracking mode to TRAFFIC
sopasCmdVec[CMD_LOAD_APPLICATION_DEFAULT] = "\x02sMN mSCloadappdef\x03"; // load application default
sopasCmdVec[CMD_DEVICE_TYPE] = "\x02sRN DItype\x03"; // ask for radar device type
sopasCmdVec[CMD_ORDER_NUMBER] = "\x02sRN OrdNum\x03"; // ask for radar order number
sopasCmdVec[CMD_START_MEASUREMENT] = "\x02sMN LMCstartmeas\x03";
sopasCmdVec[CMD_STOP_MEASUREMENT] = "\x02sMN LMCstopmeas\x03";
sopasCmdVec[CMD_APPLICATION_MODE_FIELD_OFF] = "\x02sWN SetActiveApplications 1 FEVL 0\x03"; // <STX>sWN{SPC}SetActiveApplications{SPC}1{SPC}FEVL{SPC}1<ETX>
sopasCmdVec[CMD_APPLICATION_MODE_RANGING_ON] = "\x02sWN SetActiveApplications 1 RANG 1\x03";
sopasCmdVec[CMD_SET_TO_COLA_A_PROTOCOL] = "\x02sWN EIHstCola 0\x03";
sopasCmdVec[CMD_GET_PARTIAL_SCANDATA_CFG] = "\x02sRN LMDscandatacfg\x03";
sopasCmdVec[CMD_SET_TO_COLA_B_PROTOCOL] = "\x02sWN EIHstCola 1\x03";
// defining cmd mask for cmds with variable input
sopasCmdMaskVec[CMD_SET_PARTICLE_FILTER] = "\x02sWN LFPparticle %d %d\x03";
sopasCmdMaskVec[CMD_SET_MEAN_FILTER] = "\x02sWN LFPmeanfilter %d +%d 1\x03";
sopasCmdMaskVec[CMD_ALIGNMENT_MODE] = "\x02sWN MMAlignmentMode %d\x03";
sopasCmdMaskVec[CMD_APPLICATION_MODE] = "\x02sWN SetActiveApplications 1 %s %d\x03";
sopasCmdMaskVec[CMD_SET_OUTPUT_RANGES] = "\x02sWN LMPoutputRange 1 %X %X %X\x03";
sopasCmdMaskVec[CMD_SET_PARTIAL_SCANDATA_CFG] = "\x02sWN LMDscandatacfg %02d 00 %d %d 0 00 00 0 0 0 0 1\x03";
sopasCmdMaskVec[CMD_SET_ECHO_FILTER] = "\x02sWN FREchoFilter %d\x03";
//error Messages
sopasCmdErrMsg[CMD_DEVICE_IDENT_LEGACY] = "Error reading device ident";
sopasCmdErrMsg[CMD_DEVICE_IDENT] = "Error reading device ident for MRS-family";
sopasCmdErrMsg[CMD_SERIAL_NUMBER] = "Error reading SerialNumber";
sopasCmdErrMsg[CMD_FIRMWARE_VERSION] = "Error reading FirmwareVersion";
sopasCmdErrMsg[CMD_DEVICE_STATE] = "Error reading SCdevicestate";
sopasCmdErrMsg[CMD_OPERATION_HOURS] = "Error reading operation hours";
sopasCmdErrMsg[CMD_POWER_ON_COUNT] = "Error reading operation power on counter";
sopasCmdErrMsg[CMD_LOCATION_NAME] = "Error reading Locationname";
sopasCmdErrMsg[CMD_ACTIVATE_STANDBY] = "Error acticvating Standby";
sopasCmdErrMsg[CMD_SET_PARTICLE_FILTER] = "Error setting Particelefilter";
sopasCmdErrMsg[CMD_SET_MEAN_FILTER] = "Error setting Meanfilter";
sopasCmdErrMsg[CMD_ALIGNMENT_MODE] = "Error setting Alignmentmode";
sopasCmdErrMsg[CMD_APPLICATION_MODE] = "Error setting Meanfilter";
sopasCmdErrMsg[CMD_SET_ACCESS_MODE_3] = "Error Access Mode";
sopasCmdErrMsg[CMD_SET_OUTPUT_RANGES] = "Error setting angular ranges";
sopasCmdErrMsg[CMD_GET_OUTPUT_RANGES] = "Error reading angle range";
sopasCmdErrMsg[CMD_RUN] = "FATAL ERROR unable to start RUN mode!";
sopasCmdErrMsg[CMD_SET_PARTIAL_SCANDATA_CFG] = "Error setting Scandataconfig";
sopasCmdErrMsg[CMD_STOP_SCANDATA] = "Error stopping scandata output";
sopasCmdErrMsg[CMD_START_SCANDATA] = "Error starting Scandata output";
// ML: Add hier more useful cmd and mask entries
// After definition of command, we specify the command sequence for scanner initalisation
// try for MRS1104
sopasCmdChain.push_back(CMD_SET_ACCESS_MODE_3);
if (parser_->getCurrentParamPtr()->getUseBinaryProtocol())
{
sopasCmdChain.push_back(CMD_SET_TO_COLA_B_PROTOCOL);
}
else
{
//for binary Mode Testing
sopasCmdChain.push_back(CMD_SET_TO_COLA_A_PROTOCOL);
}
bool tryToStopMeasurement = true;
if (parser_->getCurrentParamPtr()->getNumberOfLayers() == 1)
{
tryToStopMeasurement = false;
// do not stop measurement for TiM571 otherwise the scanner would not start after start measurement
// do not change the application - not supported for TiM5xx
}
if (parser_->getCurrentParamPtr()->getDeviceIsRadar() == true)
{
sopasCmdChain.push_back(CMD_LOAD_APPLICATION_DEFAULT); // load application default for radar
tryToStopMeasurement = false;
// do not stop measurement for RMS320 - the RMS320 does not support the stop command
}
if (tryToStopMeasurement)
{
sopasCmdChain.push_back(CMD_STOP_MEASUREMENT);
int numberOfLayers = parser_->getCurrentParamPtr()->getNumberOfLayers();
if ((numberOfLayers == 4) || (numberOfLayers == 24))
{
// just measuring - Application setting not supported
// "Old" device ident command "SRi 0" not supported
sopasCmdChain.push_back(CMD_DEVICE_IDENT);
}
else
{
sopasCmdChain.push_back(CMD_APPLICATION_MODE_FIELD_OFF);
sopasCmdChain.push_back(CMD_APPLICATION_MODE_RANGING_ON);
sopasCmdChain.push_back(CMD_DEVICE_IDENT_LEGACY);
sopasCmdChain.push_back(CMD_SERIAL_NUMBER);
}
}
sopasCmdChain.push_back(CMD_FIRMWARE_VERSION); // read firmware
sopasCmdChain.push_back(CMD_DEVICE_STATE); // read device state
sopasCmdChain.push_back(CMD_OPERATION_HOURS); // read operation hours
sopasCmdChain.push_back(CMD_POWER_ON_COUNT); // read power on count
sopasCmdChain.push_back(CMD_LOCATION_NAME); // read location name
return(0);
}
/*!
\brief initialize scanner
\return exit code
*/
int SickScanCommon::init_scanner()
{
const int MAX_STR_LEN = 1024;
int maxNumberOfEchos = 1;
maxNumberOfEchos = this->parser_->getCurrentParamPtr()->getNumberOfMaximumEchos(); // 1 for TIM 571, 3 for MRS1104, 5 for 6000
bool rssiFlag = false;
bool rssiResolutionIs16Bit = true; //True=16 bit Flase=8bit
int activeEchos = 0;
ros::NodeHandle pn("~");
pn.getParam("intensity", rssiFlag);
pn.getParam("intensity_resolution_16bit", rssiResolutionIs16Bit);
this->parser_->getCurrentParamPtr()->setIntensityResolutionIs16Bit(rssiResolutionIs16Bit);
// parse active_echos entry and set flag array
pn.getParam("active_echos", activeEchos);
ROS_INFO("Parameter setting for <active_echo: %d>", activeEchos);
std::vector<bool> outputChannelFlag;
outputChannelFlag.resize(maxNumberOfEchos);
int i;
int numOfFlags = 0;
for (i = 0; i < outputChannelFlag.size(); i++)
{
/*
After consultation with the company SICK,
all flags are set to true because the firmware currently does not support single selection of targets.
The selection of the echoes takes place via FREchoFilter.
*/
/* former implementation
if (activeEchos & (1 << i))
{
outputChannelFlag[i] = true;
numOfFlags++;
}
else
{
outputChannelFlag[i] = false;
}
*/
outputChannelFlag[i] = true; // always true (see comment above)
numOfFlags++;
}
if (numOfFlags == 0) // Fallback-Solution
{
outputChannelFlag[0] = true;
numOfFlags = 1;
ROS_WARN("Activate at least one echo.");
}
int result;
//================== DEFINE ANGULAR SETTING ==========================
int angleRes10000th = 0;
int angleStart10000th = 0;
int angleEnd10000th = 0;
// Mainloop for initial SOPAS cmd-Handling
//
// To add new commands do the followings:
// 1. Define new enum-entry in the enumumation "enum SOPAS_CMD" in the file sick_scan_common.h
// 2. Define new command sequence in the member function init_cmdTables()
// 3. Add cmd-id in the sopasCmdChain to trigger sending of command.
// 4. Add handling of reply by using for the pattern "REPLY_HANDLING" in this code and adding a new case instruction.
// That's all!
volatile bool useBinaryCmd = false;
if (this->parser_->getCurrentParamPtr()->getUseBinaryProtocol()) // hard coded for every scanner type
{
useBinaryCmd = true; // shall we talk ascii or binary with the scanner type??
}
bool useBinaryCmdNow = false;
int maxCmdLoop = 2; // try binary and ascii during startup
const int shortTimeOutInMs = 5000; // during startup phase to check binary or ascii
const int defaultTimeOutInMs = 20000; // standard time out 20 sec.
setReadTimeOutInMs(shortTimeOutInMs);
bool restartDueToProcolChange = false;
for (int i = 0; i < this->sopasCmdChain.size(); i++)
{
ros::Duration(0.2).sleep(); // could maybe removed
int cmdId = sopasCmdChain[i]; // get next command
std::string sopasCmd = sopasCmdVec[cmdId];
std::vector<unsigned char> replyDummy;
std::vector<unsigned char> reqBinary;
ROS_DEBUG("Command: %s", stripControl(sopasCmd).c_str());
// switch to either binary or ascii after switching the command mode
// via ... command
for (int iLoop = 0; iLoop < maxCmdLoop; iLoop++)
{
if (iLoop == 0)
{
useBinaryCmdNow = useBinaryCmd; // start with expected value
}
else
{
useBinaryCmdNow = !useBinaryCmdNow;// try the other option
useBinaryCmd = useBinaryCmdNow; // and use it from now on as default
}
this->setProtocolType(useBinaryCmdNow ? CoLa_B : CoLa_A);
if (useBinaryCmdNow)
{
this->convertAscii2BinaryCmd(sopasCmd.c_str(), &reqBinary);
result = sendSopasAndCheckAnswer(reqBinary, &replyDummy);
sopasReplyBinVec[cmdId] = replyDummy;
}
else
{
result = sendSopasAndCheckAnswer(sopasCmd.c_str(), &replyDummy);
}
if (result == 0) // command sent successfully
{
// useBinaryCmd holds information about last successful command mode
break;
}
}
if (result != 0)
{
ROS_ERROR("%s", sopasCmdErrMsg[cmdId].c_str());
diagnostics_.broadcast(getDiagnosticErrorCode(), sopasCmdErrMsg[cmdId]);
}
else
{
sopasReplyStrVec[cmdId] = replyToString(replyDummy);
}
//============================================
// Handle reply of specific commands here by inserting new case instruction
// REPLY_HANDLING
//============================================
maxCmdLoop = 1;
switch (cmdId)
{
case CMD_SET_TO_COLA_A_PROTOCOL:
{
bool protocolCheck = checkForProtocolChangeAndMaybeReconnect(useBinaryCmdNow);
if (false == protocolCheck)
{
restartDueToProcolChange = true;
}
useBinaryCmd = useBinaryCmdNow;
setReadTimeOutInMs(defaultTimeOutInMs);
}
break;
case CMD_SET_TO_COLA_B_PROTOCOL:
{
bool protocolCheck = checkForProtocolChangeAndMaybeReconnect(useBinaryCmdNow);
if (false == protocolCheck)
{
restartDueToProcolChange = true;
}
useBinaryCmd = useBinaryCmdNow;
setReadTimeOutInMs(defaultTimeOutInMs);
}
break;
/*
SERIAL_NUMBER: Device ident must be read before!
*/