Skip to content

Commit dc844b4

Browse files
authored
Merge pull request #45 from dniewinski/infinite_range
Added inf to be set for min range
2 parents dec2cdb + fdc3d48 commit dc844b4

File tree

2 files changed

+23
-8
lines changed

2 files changed

+23
-8
lines changed

launch/LMS1xx.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
<launch>
22
<arg name="host" default="192.168.1.14" />
3+
<arg name="publish_min_range_as_inf" default="false" />
34
<node pkg="lms1xx" name="lms1xx" type="LMS1xx_node">
45
<param name="host" value="$(arg host)" />
6+
<param name="publish_min_range_as_inf" value="$(arg publish_min_range_as_inf)" />
57
</node>
68
</launch>

src/LMS1xx_node.cpp

Lines changed: 21 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,8 @@
2626
#include <LMS1xx/LMS1xx.h>
2727
#include "ros/ros.h"
2828
#include "sensor_msgs/LaserScan.h"
29+
#include <limits>
30+
#include <string>
2931

3032
#define DEG2RAD M_PI/180.0
3133

@@ -41,6 +43,7 @@ int main(int argc, char **argv)
4143
// parameters
4244
std::string host;
4345
std::string frame_id;
46+
bool inf_range;
4447
int port;
4548

4649
ros::init(argc, argv, "lms1xx");
@@ -50,6 +53,7 @@ int main(int argc, char **argv)
5053

5154
n.param<std::string>("host", host, "192.168.1.2");
5255
n.param<std::string>("frame_id", frame_id, "laser");
56+
n.param<bool>("publish_min_range_as_inf", inf_range, false);
5357
n.param<int>("port", port, 2111);
5458

5559
while (ros::ok())
@@ -87,15 +91,15 @@ int main(int argc, char **argv)
8791
scan_msg.range_min = 0.01;
8892
scan_msg.range_max = 20.0;
8993
scan_msg.scan_time = 100.0 / cfg.scaningFrequency;
90-
scan_msg.angle_increment = (double)outputRange.angleResolution / 10000.0 * DEG2RAD;
91-
scan_msg.angle_min = (double)outputRange.startAngle / 10000.0 * DEG2RAD - M_PI / 2;
92-
scan_msg.angle_max = (double)outputRange.stopAngle / 10000.0 * DEG2RAD - M_PI / 2;
94+
scan_msg.angle_increment = static_cast<double>(outputRange.angleResolution / 10000.0 * DEG2RAD);
95+
scan_msg.angle_min = static_cast<double>(outputRange.startAngle / 10000.0 * DEG2RAD - M_PI / 2);
96+
scan_msg.angle_max = static_cast<double>(outputRange.stopAngle / 10000.0 * DEG2RAD - M_PI / 2);
9397

9498
ROS_DEBUG_STREAM("Device resolution is " << (double)outputRange.angleResolution / 10000.0 << " degrees.");
9599
ROS_DEBUG_STREAM("Device frequency is " << (double)cfg.scaningFrequency / 100.0 << " Hz");
96100

97101
int angle_range = outputRange.stopAngle - outputRange.startAngle;
98-
int num_values = angle_range / outputRange.angleResolution ;
102+
int num_values = angle_range / outputRange.angleResolution;
99103
if (angle_range % outputRange.angleResolution == 0)
100104
{
101105
// Include endpoint
@@ -128,8 +132,8 @@ int main(int argc, char **argv)
128132
ROS_DEBUG("Waiting for ready status.");
129133
ros::Time ready_status_timeout = ros::Time::now() + ros::Duration(5);
130134

131-
//while(1)
132-
//{
135+
// while(1)
136+
// {
133137
status_t stat = laser.queryStatus();
134138
ros::Duration(1.0).sleep();
135139
if (stat != ready_for_measurement)
@@ -160,7 +164,7 @@ int main(int argc, char **argv)
160164
}*/
161165

162166
ROS_DEBUG("Starting device.");
163-
laser.startDevice(); // Log out to properly re-enable system after config
167+
laser.startDevice(); // Log out to properly re-enable system after config
164168

165169
ROS_DEBUG("Commanding continuous measurements.");
166170
laser.scanContinous(1);
@@ -178,7 +182,16 @@ int main(int argc, char **argv)
178182
{
179183
for (int i = 0; i < data.dist_len1; i++)
180184
{
181-
scan_msg.ranges[i] = data.dist1[i] * 0.001;
185+
float range_data = data.dist1[i] * 0.001;
186+
187+
if (inf_range && range_data < scan_msg.range_min)
188+
{
189+
scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
190+
}
191+
else
192+
{
193+
scan_msg.ranges[i] = range_data;
194+
}
182195
}
183196

184197
for (int i = 0; i < data.rssi_len1; i++)

0 commit comments

Comments
 (0)