Skip to content
This repository was archived by the owner on Mar 8, 2023. It is now read-only.

Commit d1e6d93

Browse files
committed
Release 1.9.0 field monitoring for TiM7xx and TiM7xxS
1 parent d3634ac commit d1e6d93

File tree

12 files changed

+129
-103
lines changed

12 files changed

+129
-103
lines changed

CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66
cmake_minimum_required(VERSION 2.8.3)
77

88
# build options: set OFF for relese version, ON for development and test
9-
option(ENABLE_EMULATOR "Build emulator for offline and unittests" OFF) # OFF (release) or ON (development)
10-
option(BUILD_DEBUG_TARGET "Build debug target" OFF) # OFF (release) or ON (development)
9+
option(ENABLE_EMULATOR "Build emulator for offline and unittests" ON) # OFF (release) or ON (development)
10+
option(BUILD_DEBUG_TARGET "Build debug target" ON) # OFF (release) or ON (development)
1111

1212
# set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall")
1313
# set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wpedantic")

README.md

100644100755
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -213,7 +213,7 @@ The use of the parameters can be looked up in the launch files. This is also rec
213213

214214
- Angle compensation: For highest angle accuracy the NAV-Lidar series supports an [angle compensation mechanism](./doc/angular_compensation.md).
215215

216-
- The **TiM7xxS** family has [extended settings for field monitoring](./doc/tim7xxs_extensions.md).
216+
- The **TiM7xx** and **TiM7xxS** families have [extended settings for field monitoring](./doc/tim7xxs_extensions.md).
217217

218218
## Sopas Mode
219219
This driver supports both COLA-B (binary) and COLA-A (ASCII) communication with the laser scanner. Binary mode is activated by default. Since this mode generates less network traffic.

doc/tim7xxs_extensions.md

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
# Extensions for TiM7xxS
22

3-
The TiM7xxS family has the following extended settings for field monitoring:
3+
The TiM7xx and TiM7xxS families have the following extended settings for field monitoring:
44

55
## Field monitoring messages
66

7-
TiM7xxS scanner support field monitoring. Fields can be configured by Sopas ET. Once they are configured, sick_scan publishes ros messages containing the monitoring information from the lidar.
7+
TiM7xx and TiM7xxS scanner support field monitoring. Fields can be configured by Sopas ET. Once they are configured, sick_scan publishes ros messages containing the monitoring information from the lidar.
88

9-
By default, field monitoring is enabled in the launch file [sick_tim_7xxS.launch](../launch/sick_tim_7xxS.launch) by following settings:
9+
By default, field monitoring is enabled in the launch file [sick_tim_7xx.launch](../launch/sick_tim_7xx.launch) resp. [sick_tim_7xxS.launch](../launch/sick_tim_7xxS.launch) by following settings:
1010
```
1111
<param name="activate_lferec" type="bool" value="True"/> <!-- activate field monitoring by lferec messages -->
1212
<param name="activate_lidoutputstate" type="bool" value="True"/> <!-- activate field monitoring by lidoutputstate messages -->

driver/src/sick_generic_parser.cpp

Lines changed: 22 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -332,21 +332,24 @@ namespace sick_scan
332332
return (useSafetyPasWD);
333333
}
334334

335-
bool ScannerBasicParam::getUseSafetyFields(){
336-
return(useSafetyFields);
335+
EVAL_FIELD_SUPPORT ScannerBasicParam::getUseEvalFields()
336+
{
337+
return this->useEvalFields;
337338
}
338339

339-
void ScannerBasicParam::setUseSafetyFields(bool _useSafetyFields){
340-
this->useSafetyFields=_useSafetyFields;
340+
void ScannerBasicParam::setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields)
341+
{
342+
this->useEvalFields = _useEvalFields;
341343
}
344+
342345
/*!
343346
\brief Construction of parameter object
344347
345348
*/
346349
ScannerBasicParam::ScannerBasicParam()
347350
: numberOfLayers(0), numberOfShots(0), numberOfMaximumEchos(0), elevationDegreeResolution(0), angleDegressResolution(0), expectedFrequency(0),
348351
useBinaryProtocol(false), IntensityResolutionIs16Bit(false), deviceIsRadar(false), useSafetyPasWD(false), encoderMode(0),
349-
CartographerCompatibility(false), scanMirroredAndShifted(false), useSafetyFields(false)
352+
CartographerCompatibility(false), scanMirroredAndShifted(false), useEvalFields(EVAL_FIELD_UNSUPPORTED)
350353
{
351354
this->elevationDegreeResolution = 0.0;
352355
this->setUseBinaryProtocol(false);
@@ -420,7 +423,7 @@ namespace sick_scan
420423
basicParams[i].setUseSafetyPasWD(false); // Default
421424
basicParams[i].setEncoderMode(-1); // Default
422425
basicParams[i].setScanMirroredAndShifted(false);
423-
basicParams[i].setUseSafetyFields(false);
426+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
424427
}
425428
if (basicParams[i].getScannerName().compare(SICK_SCANNER_LMS_1XXX_NAME) ==
426429
0) // LMS1000 - 4 layer, 1101 shots per scan
@@ -436,7 +439,7 @@ namespace sick_scan
436439
basicParams[i].setUseSafetyPasWD(false); // Default
437440
basicParams[i].setEncoderMode(-1); // Default
438441
basicParams[i].setScanMirroredAndShifted(false);
439-
basicParams[i].setUseSafetyFields(false);
442+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
440443
}
441444
if (basicParams[i].getScannerName().compare(SICK_SCANNER_TIM_240_NAME) ==
442445
0) // TIM_5xx - 1 Layer, max. 811 shots per scan
@@ -451,7 +454,7 @@ namespace sick_scan
451454
basicParams[i].setUseSafetyPasWD(false); // Default
452455
basicParams[i].setEncoderMode(-1); // Default
453456
basicParams[i].setScanMirroredAndShifted(false);
454-
basicParams[i].setUseSafetyFields(false);
457+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
455458

456459
}
457460
if (basicParams[i].getScannerName().compare(SICK_SCANNER_TIM_5XX_NAME) ==
@@ -467,8 +470,7 @@ namespace sick_scan
467470
basicParams[i].setUseSafetyPasWD(false); // Default
468471
basicParams[i].setEncoderMode(-1); // Default
469472
basicParams[i].setScanMirroredAndShifted(false);
470-
basicParams[i].setUseSafetyFields(false);
471-
473+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
472474
}
473475
if (basicParams[i].getScannerName().compare(SICK_SCANNER_LMS_4XXX_NAME) == 0) // LMS_4xxx - 1 Layer, 600 Hz
474476
{
@@ -482,7 +484,7 @@ namespace sick_scan
482484
basicParams[i].setUseSafetyPasWD(false); // Default
483485
basicParams[i].setEncoderMode(-1); // Default
484486
basicParams[i].setScanMirroredAndShifted(false);
485-
basicParams[i].setUseSafetyFields(false);
487+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
486488
}
487489
if (basicParams[i].getScannerName().compare(SICK_SCANNER_TIM_7XX_NAME) == 0) // TIM_7xx - 1 Layer Scanner
488490
{
@@ -496,7 +498,7 @@ namespace sick_scan
496498
basicParams[i].setUseSafetyPasWD(false); // Default
497499
basicParams[i].setEncoderMode(-1); // Default
498500
basicParams[i].setScanMirroredAndShifted(false);
499-
basicParams[i].setUseSafetyFields(false);
501+
basicParams[i].setUseEvalFields(USE_EVAL_FIELD_TIM7XX_LOGIC);
500502
}
501503
if (basicParams[i].getScannerName().compare(SICK_SCANNER_TIM_7XXS_NAME) == 0) // TIM_7xxS - 1 layer Safety Scanner
502504
{
@@ -510,7 +512,7 @@ namespace sick_scan
510512
basicParams[i].setUseSafetyPasWD(true); // Safety scanner
511513
basicParams[i].setEncoderMode(-1); // Default
512514
basicParams[i].setScanMirroredAndShifted(false);
513-
basicParams[i].setUseSafetyFields(true);
515+
basicParams[i].setUseEvalFields(USE_EVAL_FIELD_TIM7XX_LOGIC);
514516
}
515517
if (basicParams[i].getScannerName().compare(SICK_SCANNER_LMS_5XX_NAME) == 0) // LMS_5xx - 1 Layer
516518
{
@@ -524,7 +526,7 @@ namespace sick_scan
524526
basicParams[i].setUseSafetyPasWD(false); // Default
525527
basicParams[i].setEncoderMode(-1); // Default
526528
basicParams[i].setScanMirroredAndShifted(false);
527-
basicParams[i].setUseSafetyFields(false);
529+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
528530
}
529531
if (basicParams[i].getScannerName().compare(SICK_SCANNER_LMS_1XX_NAME) == 0) // LMS_1xx - 1 Layer
530532
{
@@ -538,7 +540,7 @@ namespace sick_scan
538540
basicParams[i].setUseSafetyPasWD(false); // Default
539541
basicParams[i].setEncoderMode(-1); // Default
540542
basicParams[i].setScanMirroredAndShifted(false);
541-
basicParams[i].setUseSafetyFields(false);
543+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
542544
}
543545
if (basicParams[i].getScannerName().compare(SICK_SCANNER_MRS_6XXX_NAME) == 0) //
544546
{
@@ -553,7 +555,7 @@ namespace sick_scan
553555
basicParams[i].setUseSafetyPasWD(false); // Default
554556
basicParams[i].setEncoderMode(-1); // Default
555557
basicParams[i].setScanMirroredAndShifted(false);
556-
basicParams[i].setUseSafetyFields(false);
558+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
557559
}
558560

559561
if (basicParams[i].getScannerName().compare(SICK_SCANNER_RMS_3XX_NAME) == 0) // Radar
@@ -569,7 +571,7 @@ namespace sick_scan
569571
basicParams[i].setUseSafetyPasWD(false); // Default
570572
basicParams[i].setEncoderMode(-1); // Default
571573
basicParams[i].setScanMirroredAndShifted(false);
572-
basicParams[i].setUseSafetyFields(false);
574+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
573575
}
574576
if (basicParams[i].getScannerName().compare(SICK_SCANNER_NAV_3XX_NAME) == 0) // Nav 3xx
575577
{
@@ -581,7 +583,7 @@ namespace sick_scan
581583
basicParams[i].setUseBinaryProtocol(true);
582584
basicParams[i].setDeviceIsRadar(false); // Default
583585
basicParams[i].setScanMirroredAndShifted(true);
584-
basicParams[i].setUseSafetyFields(false);
586+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
585587
}
586588
if (basicParams[i].getScannerName().compare(SICK_SCANNER_NAV_2XX_NAME) == 0) // NAV_2xx - 1 Layer
587589
{
@@ -595,7 +597,7 @@ namespace sick_scan
595597
basicParams[i].setUseSafetyPasWD(false); // Default
596598
basicParams[i].setEncoderMode(-1); // Default
597599
basicParams[i].setScanMirroredAndShifted(false);
598-
basicParams[i].setUseSafetyFields(false);
600+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
599601
}
600602
if (basicParams[i].getScannerName().compare(SICK_SCANNER_TIM_4XX_NAME) == 0) // TiM433 and TiM443
601603
{
@@ -609,7 +611,7 @@ namespace sick_scan
609611
basicParams[i].setUseSafetyPasWD(false); // Default
610612
basicParams[i].setEncoderMode(-1); // Default
611613
basicParams[i].setScanMirroredAndShifted(false);
612-
basicParams[i].setUseSafetyFields(false);
614+
basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED);
613615
}
614616
}
615617

driver/src/sick_scan_common.cpp

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -371,7 +371,7 @@ namespace sick_scan
371371
publish_lferec_ = false;
372372
publish_lidoutputstate_ = false;
373373
const std::string scannername = parser_->getCurrentParamPtr()->getScannerName();
374-
if (scannername.compare(SICK_SCANNER_TIM_7XXS_NAME) == 0)
374+
if (parser_->getCurrentParamPtr()->getUseEvalFields() == USE_EVAL_FIELD_TIM7XX_LOGIC)
375375
{
376376
lferec_pub_ = nh_.advertise<sick_scan::LFErecMsg>(scannername + "/lferec", 100);
377377
lidoutputstate_pub_ = nh_.advertise<sick_scan::LIDoutputstateMsg>(scannername + "/lidoutputstate", 100);
@@ -435,7 +435,7 @@ namespace sick_scan
435435
printf("\nSOPAS - Stopped streaming scan data.\n");
436436
}
437437

438-
if (parser_->getCurrentParamPtr()->getScannerName().compare(SICK_SCANNER_TIM_7XXS_NAME) == 0)
438+
if (parser_->getCurrentParamPtr()->getUseEvalFields() == USE_EVAL_FIELD_TIM7XX_LOGIC)
439439
{
440440
if(sendSOPASCommand("\x02sEN LFErec 0\x03", NULL) != 0 // TiM781S: deactivate LFErec messages, send "sEN LFErec 0"
441441
|| sendSOPASCommand("\x02sEN LIDoutputstate 0\x03", NULL) != 0 // TiM781S: deactivate LIDoutputstate messages, send "sEN LIDoutputstate 0"
@@ -1170,13 +1170,11 @@ namespace sick_scan
11701170

11711171
bool rssiFlag = false;
11721172
bool rssiResolutionIs16Bit = true; //True=16 bit Flase=8bit
1173-
// bool useSafetyfields=false;
11741173
int activeEchos = 0;
11751174
ros::NodeHandle pn("~");
11761175

11771176
pn.getParam("intensity", rssiFlag);
11781177
pn.getParam("intensity_resolution_16bit", rssiResolutionIs16Bit);
1179-
// pn.getParam("use_safety_fields", useSafetyfields);
11801178
//check new ip adress and add cmds to write ip to comand chain
11811179
std::string sNewIPAddr = "";
11821180
boost::asio::ip::address_v4 ipNewIPAddr;
@@ -1215,7 +1213,6 @@ namespace sick_scan
12151213
}
12161214

12171215
this->parser_->getCurrentParamPtr()->setIntensityResolutionIs16Bit(rssiResolutionIs16Bit);
1218-
// this->parser_->getCurrentParamPtr()->setUseSafetyFields(useSafetyfields);
12191216
// parse active_echos entry and set flag array
12201217
pn.getParam("active_echos", activeEchos);
12211218

@@ -2106,7 +2103,7 @@ namespace sick_scan
21062103

21072104
}
21082105
//SAFTY FIELD PARSING
2109-
if (this->parser_->getCurrentParamPtr()->getUseSafetyFields())
2106+
if (this->parser_->getCurrentParamPtr()->getUseEvalFields() == USE_EVAL_FIELD_TIM7XX_LOGIC)
21102107
{
21112108
ROS_INFO("Reading safety fields");
21122109
SickScanFieldMonSingleton *fieldMon = SickScanFieldMonSingleton::getInstance();
@@ -2443,7 +2440,7 @@ namespace sick_scan
24432440
startProtocolSequence.push_back(CMD_RUN); // leave user level
24442441
startProtocolSequence.push_back(CMD_START_SCANDATA);
24452442

2446-
if (parser_->getCurrentParamPtr()->getScannerName().compare(SICK_SCANNER_TIM_7XXS_NAME) == 0)
2443+
if (parser_->getCurrentParamPtr()->getUseEvalFields() == USE_EVAL_FIELD_TIM7XX_LOGIC)
24472444
{
24482445

24492446
// Activate LFErec, LIDoutputstate and LIDinputstate messages

include/sick_scan/sick_generic_parser.h

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,15 @@
5858
// namespace sensor_msgs
5959
namespace sick_scan
6060
{
61+
enum EVAL_FIELD_SUPPORT // type of eval field support:
62+
{
63+
EVAL_FIELD_UNSUPPORTED = 0, // Lidar does not support eval field (default)
64+
USE_EVAL_FIELD_TIM7XX_LOGIC, // eval fields supported by TiM7xx and TiM7xxS
65+
USE_EVAL_FIELD_LMS5XX_LOGIC, // eval fields supported by LMS5XX
66+
USE_EVAL_FIELD_LMS5XX_UNSUPPORTED, // eval fields not supported by LMS5XX
67+
USE_EVAL_FIELD_NUM // max number of eval field support types
68+
};
69+
6170
class ScannerBasicParam
6271
{
6372
public:
@@ -115,9 +124,9 @@ namespace sick_scan
115124

116125
int8_t getEncoderMode();
117126

118-
bool getUseSafetyFields();
127+
EVAL_FIELD_SUPPORT getUseEvalFields();
119128

120-
void setUseSafetyFields(bool _useSafetyFields);
129+
void setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields);
121130

122131
private:
123132
std::string scannerName;
@@ -134,7 +143,7 @@ namespace sick_scan
134143
int8_t encoderMode;
135144
bool CartographerCompatibility;
136145
bool scanMirroredAndShifted;
137-
bool useSafetyFields;
146+
EVAL_FIELD_SUPPORT useEvalFields;
138147
};
139148

140149

launch/sick_tim_7xx.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,10 @@
3636
<param name="frame_id" type="str" value="$(arg frame_id)"/>
3737
<param name="port" type="string" value="2112"/>
3838
<param name="timelimit" type="int" value="5"/>
39+
<param name="start_services" type="bool" value="True"/> <!-- start ros service for cola commands -->
40+
<param name="activate_lferec" type="bool" value="True"/> <!-- activate field monitoring by lferec messages -->
41+
<param name="activate_lidoutputstate" type="bool" value="True"/> <!-- activate field monitoring by lidoutputstate messages -->
42+
<param name="activate_lidinputstate" type="bool" value="True"/> <!-- activate field monitoring by lidinputstate messages -->
3943
</node>
4044

4145
</launch>

launch/sick_tim_7xxS.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@
3636
<param name="frame_id" type="str" value="$(arg frame_id)"/>
3737
<param name="port" type="string" value="2112"/>
3838
<param name="timelimit" type="int" value="5"/>
39-
<param name="start_services" type="bool" value="True"/>
39+
<param name="start_services" type="bool" value="True"/> <!-- start ros service for cola commands -->
4040
<param name="activate_lferec" type="bool" value="True"/> <!-- activate field monitoring by lferec messages -->
4141
<param name="activate_lidoutputstate" type="bool" value="True"/> <!-- activate field monitoring by lidoutputstate messages -->
4242
<param name="activate_lidinputstate" type="bool" value="True"/> <!-- activate field monitoring by lidinputstate messages -->

test/emulator/config/rviz_emulator_cfg.rviz

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ Panels:
88
- /PointCloud21
99
- /Axes1
1010
- /MarkerArray1
11+
- /MarkerArray2
1112
Splitter Ratio: 0.5
1213
Tree Height: 799
1314
- Class: rviz/Selection
@@ -70,7 +71,7 @@ Visualization Manager:
7071
Enabled: true
7172
Invert Rainbow: false
7273
Max Color: 255; 255; 255
73-
Max Intensity: 39172
74+
Max Intensity: 38513
7475
Min Color: 0; 0; 0
7576
Min Intensity: 0
7677
Name: PointCloud2
@@ -94,12 +95,20 @@ Visualization Manager:
9495
Value: true
9596
- Class: rviz/MarkerArray
9697
Enabled: true
97-
Marker Topic: /sick_tim_7xxS/marker
98+
Marker Topic: /sick_tim_7xx/marker
9899
Name: MarkerArray
99100
Namespaces:
100101
sick_scan: true
101102
Queue Size: 100
102103
Value: true
104+
- Class: rviz/MarkerArray
105+
Enabled: true
106+
Marker Topic: /sick_tim_7xxS/marker
107+
Name: MarkerArray
108+
Namespaces:
109+
{}
110+
Queue Size: 100
111+
Value: true
103112
Enabled: true
104113
Global Options:
105114
Background Color: 48; 48; 48

0 commit comments

Comments
 (0)