From 9753e6879be7e57a72a0d6cafbb1ad717a074756 Mon Sep 17 00:00:00 2001 From: rostest Date: Tue, 13 Jul 2021 16:18:33 +0200 Subject: [PATCH] Option min_intensity #131 --- README.md | 3 +++ cfg/SickScan.cfg | 1 + driver/src/sick_scan_common.cpp | 15 +++++++++++++++ include/sick_scan/sick_scan_common.h | 3 +++ launch/sick_lms_1xx.launch | 1 + launch/sick_lms_1xx_encoder.launch | 1 + launch/sick_lms_1xxx.launch | 1 + launch/sick_lms_4xxx.launch | 1 + launch/sick_lms_4xxx_encoder.launch | 1 + launch/sick_lms_5xx.launch | 1 + launch/sick_lms_5xx_encoder.launch | 1 + launch/sick_mrs_1xxx.launch | 1 + launch/sick_mrs_1xxx_cartographer.launch | 1 + launch/sick_mrs_6xxx.launch | 1 + launch/sick_mrs_6xxx_first_echo.launch | 1 + launch/sick_mrs_6xxx_last_echo.launch | 1 + launch/sick_mrs_6xxx_narrow.launch | 1 + launch/sick_nav_2xx.launch | 1 + launch/sick_nav_3xx.launch | 1 + launch/sick_nav_3xx_ascii.launch | 1 + launch/sick_new_ip.launch | 1 + launch/sick_rms_3xx.launch | 1 + launch/sick_rms_3xx_emul.launch | 1 + launch/sick_tim_240.launch | 1 + launch/sick_tim_240_bin.launch | 1 + launch/sick_tim_4xx.launch | 1 + launch/sick_tim_5xx.launch | 1 + launch/sick_tim_5xx_ASCII.launch | 1 + launch/sick_tim_5xx_new_ip.launch | 1 + launch/sick_tim_5xx_twin.launch | 2 ++ launch/sick_tim_7xx.launch | 1 + launch/sick_tim_7xxS.launch | 1 + 32 files changed, 51 insertions(+) diff --git a/README.md b/README.md index e57db9a..fffe451 100755 --- a/README.md +++ b/README.md @@ -196,6 +196,9 @@ The use of the parameters can be looked up in the launch files. This is also rec - `intensity_resolution_16bit` If true, the intensity values is transferred as 16 bit value. If false, as 8 bit value. +- `min_intensity` + If min_intensity > 0, all range values in a LaserScan message are set to infinity, if their intensity value is below min_intensity + - `cloud_topic` Topic name of the published pointcloud2 data diff --git a/cfg/SickScan.cfg b/cfg/SickScan.cfg index b3d2c7a..eb8bb72 100755 --- a/cfg/SickScan.cfg +++ b/cfg/SickScan.cfg @@ -57,6 +57,7 @@ gen.add("min_ang", double_t, 0, "The angle of the first range measurement gen.add("max_ang", double_t, 0, "The angle of the last range measurement [rad].", pi,-2*pi,2*pi) gen.add("intensity", bool_t, 0, "Whether or not to return intensity values. ", True) gen.add("intensity_resolution_16bit", bool_t, 0, "True = 16Bit False = 8Bit. ", True) +gen.add("min_intensity", double_t, 0, "Set range of LaserScan messages to infinity, if intensity < min_intensity", 0.0, 0.0, 65536.0) gen.add("skip", int_t, 0, "The number of scans to skip between each measured scan.", 0, 0, 9) gen.add("frame_id", str_t, 0, "The TF frame in which laser scans will be returned.", "laser") gen.add("imu_frame_id", str_t, 0, "The TF frame in which imu_data will be returned.", "imu_link") diff --git a/driver/src/sick_scan_common.cpp b/driver/src/sick_scan_common.cpp index ed44230..5516037 100644 --- a/driver/src/sick_scan_common.cpp +++ b/driver/src/sick_scan_common.cpp @@ -337,6 +337,7 @@ namespace sick_scan // FIXME All Tims have 15Hz { expectedFrequency_ = this->parser_->getCurrentParamPtr()->getExpectedFrequency(); + m_min_intensity = 0.0; // Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) setSensorIsRadar(false); init_cmdTables(); @@ -1177,6 +1178,8 @@ namespace sick_scan pn.getParam("intensity", rssiFlag); pn.getParam("intensity_resolution_16bit", rssiResolutionIs16Bit); + pn.getParam("min_intensity", m_min_intensity); // Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) + //check new ip adress and add cmds to write ip to comand chain std::string sNewIPAddr = ""; boost::asio::ip::address_v4 ipNewIPAddr; @@ -3759,6 +3762,18 @@ namespace sick_scan sendMsg = false; } } + // If msg.intensities[j] < min_intensity, then set msg.ranges[j] to inf according to https://github.com/SICKAG/sick_scan/issues/131 + if(m_min_intensity > 0) // Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) + { + for (int j = 0, j_max = (int)std::min(msg.ranges.size(), msg.intensities.size()); j < j_max; j++) + { + if(msg.intensities[j] < m_min_intensity) + { + msg.ranges[j] = std::numeric_limits::infinity(); + // ROS_DEBUG_STREAM("msg.intensities[" << j << "]=" << msg.intensities[j] << " < " << m_min_intensity << ", set msg.ranges[" << j << "]=" << msg.ranges[j] << " to infinity."); + } + } + } } #ifndef _MSC_VER diff --git a/include/sick_scan/sick_scan_common.h b/include/sick_scan/sick_scan_common.h index c65dcac..cb5aa4f 100644 --- a/include/sick_scan/sick_scan_common.h +++ b/include/sick_scan/sick_scan_common.h @@ -392,6 +392,9 @@ namespace sick_scan bool sensorIsRadar; AngleCompensator *angleCompensator = NULL; + + double m_min_intensity; // Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) + }; } /* namespace sick_scan */ diff --git a/launch/sick_lms_1xx.launch b/launch/sick_lms_1xx.launch index 3b5fd6c..110e7d4 100644 --- a/launch/sick_lms_1xx.launch +++ b/launch/sick_lms_1xx.launch @@ -19,5 +19,6 @@ + diff --git a/launch/sick_lms_1xx_encoder.launch b/launch/sick_lms_1xx_encoder.launch index d8c5734..b60ae44 100644 --- a/launch/sick_lms_1xx_encoder.launch +++ b/launch/sick_lms_1xx_encoder.launch @@ -28,5 +28,6 @@ + diff --git a/launch/sick_lms_1xxx.launch b/launch/sick_lms_1xxx.launch index 8231a0f..ffb0e07 100644 --- a/launch/sick_lms_1xxx.launch +++ b/launch/sick_lms_1xxx.launch @@ -27,5 +27,6 @@ + diff --git a/launch/sick_lms_4xxx.launch b/launch/sick_lms_4xxx.launch index 860b069..7ba3ead 100644 --- a/launch/sick_lms_4xxx.launch +++ b/launch/sick_lms_4xxx.launch @@ -58,6 +58,7 @@ + diff --git a/launch/sick_lms_4xxx_encoder.launch b/launch/sick_lms_4xxx_encoder.launch index edf7699..48e028f 100644 --- a/launch/sick_lms_4xxx_encoder.launch +++ b/launch/sick_lms_4xxx_encoder.launch @@ -59,6 +59,7 @@ + diff --git a/launch/sick_lms_5xx.launch b/launch/sick_lms_5xx.launch index 6310700..a005db7 100644 --- a/launch/sick_lms_5xx.launch +++ b/launch/sick_lms_5xx.launch @@ -52,6 +52,7 @@ Check IP-address, if you scanner is not found after roslaunch. + diff --git a/launch/sick_lms_5xx_encoder.launch b/launch/sick_lms_5xx_encoder.launch index 762c4da..386cd03 100644 --- a/launch/sick_lms_5xx_encoder.launch +++ b/launch/sick_lms_5xx_encoder.launch @@ -40,6 +40,7 @@ Check IP-address, if you scanner is not found after roslaunch. + diff --git a/launch/sick_mrs_1xxx_cartographer.launch b/launch/sick_mrs_1xxx_cartographer.launch index dcf5603..244b510 100644 --- a/launch/sick_mrs_1xxx_cartographer.launch +++ b/launch/sick_mrs_1xxx_cartographer.launch @@ -43,6 +43,7 @@ default max_angle for this scanner type is +137.5 degree. + diff --git a/launch/sick_mrs_6xxx.launch b/launch/sick_mrs_6xxx.launch index da73f87..10ce18f 100644 --- a/launch/sick_mrs_6xxx.launch +++ b/launch/sick_mrs_6xxx.launch @@ -31,6 +31,7 @@ + diff --git a/launch/sick_mrs_6xxx_first_echo.launch b/launch/sick_mrs_6xxx_first_echo.launch index 9f58b8e..202d796 100644 --- a/launch/sick_mrs_6xxx_first_echo.launch +++ b/launch/sick_mrs_6xxx_first_echo.launch @@ -28,6 +28,7 @@ + diff --git a/launch/sick_mrs_6xxx_last_echo.launch b/launch/sick_mrs_6xxx_last_echo.launch index a9b1e62..723439c 100644 --- a/launch/sick_mrs_6xxx_last_echo.launch +++ b/launch/sick_mrs_6xxx_last_echo.launch @@ -27,6 +27,7 @@ + diff --git a/launch/sick_mrs_6xxx_narrow.launch b/launch/sick_mrs_6xxx_narrow.launch index 9faed7c..e6bd474 100644 --- a/launch/sick_mrs_6xxx_narrow.launch +++ b/launch/sick_mrs_6xxx_narrow.launch @@ -29,6 +29,7 @@ + diff --git a/launch/sick_nav_2xx.launch b/launch/sick_nav_2xx.launch index ec22c28..f18b844 100644 --- a/launch/sick_nav_2xx.launch +++ b/launch/sick_nav_2xx.launch @@ -12,5 +12,6 @@ + diff --git a/launch/sick_nav_3xx.launch b/launch/sick_nav_3xx.launch index 23ed3b1..c7fa0ec 100644 --- a/launch/sick_nav_3xx.launch +++ b/launch/sick_nav_3xx.launch @@ -23,6 +23,7 @@ + diff --git a/launch/sick_nav_3xx_ascii.launch b/launch/sick_nav_3xx_ascii.launch index 2461192..d82ec89 100644 --- a/launch/sick_nav_3xx_ascii.launch +++ b/launch/sick_nav_3xx_ascii.launch @@ -20,6 +20,7 @@ + diff --git a/launch/sick_new_ip.launch b/launch/sick_new_ip.launch index 80247a6..c007d12 100644 --- a/launch/sick_new_ip.launch +++ b/launch/sick_new_ip.launch @@ -19,6 +19,7 @@ + diff --git a/launch/sick_rms_3xx.launch b/launch/sick_rms_3xx.launch index 6293818..aebc543 100644 --- a/launch/sick_rms_3xx.launch +++ b/launch/sick_rms_3xx.launch @@ -26,5 +26,6 @@ + diff --git a/launch/sick_rms_3xx_emul.launch b/launch/sick_rms_3xx_emul.launch index 7c1ae2b..d03d308 100644 --- a/launch/sick_rms_3xx_emul.launch +++ b/launch/sick_rms_3xx_emul.launch @@ -15,5 +15,6 @@ + diff --git a/launch/sick_tim_240.launch b/launch/sick_tim_240.launch index 87866a4..dd9c283 100644 --- a/launch/sick_tim_240.launch +++ b/launch/sick_tim_240.launch @@ -37,5 +37,6 @@ + diff --git a/launch/sick_tim_240_bin.launch b/launch/sick_tim_240_bin.launch index a591177..7de3751 100644 --- a/launch/sick_tim_240_bin.launch +++ b/launch/sick_tim_240_bin.launch @@ -37,5 +37,6 @@ + diff --git a/launch/sick_tim_4xx.launch b/launch/sick_tim_4xx.launch index 7c3aa3c..4759b15 100644 --- a/launch/sick_tim_4xx.launch +++ b/launch/sick_tim_4xx.launch @@ -61,6 +61,7 @@ + diff --git a/launch/sick_tim_5xx.launch b/launch/sick_tim_5xx.launch index fc280f5..b168016 100644 --- a/launch/sick_tim_5xx.launch +++ b/launch/sick_tim_5xx.launch @@ -37,6 +37,7 @@ + diff --git a/launch/sick_tim_5xx_twin.launch b/launch/sick_tim_5xx_twin.launch index d482b7d..ce6f47f 100644 --- a/launch/sick_tim_5xx_twin.launch +++ b/launch/sick_tim_5xx_twin.launch @@ -29,6 +29,7 @@ + @@ -42,6 +43,7 @@ + diff --git a/launch/sick_tim_7xx.launch b/launch/sick_tim_7xx.launch index 6327fc3..9c4ce0d 100644 --- a/launch/sick_tim_7xx.launch +++ b/launch/sick_tim_7xx.launch @@ -40,6 +40,7 @@ + diff --git a/launch/sick_tim_7xxS.launch b/launch/sick_tim_7xxS.launch index af20c21..5e20d29 100644 --- a/launch/sick_tim_7xxS.launch +++ b/launch/sick_tim_7xxS.launch @@ -40,6 +40,7 @@ +