Skip to content

Commit 5ce20ae

Browse files
author
Jacob Perron
committed
Add parameters for min/max angle
1 parent dec2cdb commit 5ce20ae

File tree

1 file changed

+36
-15
lines changed

1 file changed

+36
-15
lines changed

src/LMS1xx_node.cpp

Lines changed: 36 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ int main(int argc, char **argv)
3939
sensor_msgs::LaserScan scan_msg;
4040

4141
// parameters
42+
double angle_max;
43+
double angle_min;
4244
std::string host;
4345
std::string frame_id;
4446
int port;
@@ -48,10 +50,19 @@ int main(int argc, char **argv)
4850
ros::NodeHandle n("~");
4951
ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
5052

53+
n.param<double>("angle_max", angle_max, M_PI);
54+
n.param<double>("angle_min", angle_min, -M_PI);
5155
n.param<std::string>("host", host, "192.168.1.2");
5256
n.param<std::string>("frame_id", frame_id, "laser");
5357
n.param<int>("port", port, 2111);
5458

59+
if (angle_min > angle_max)
60+
{
61+
ROS_FATAL("Minimum angle %f exceeds maximum angle %f", angle_min, angle_max);
62+
ros::shutdown();
63+
return 1;
64+
}
65+
5566
while (ros::ok())
5667
{
5768
ROS_INFO_STREAM("Connecting to laser at " << host);
@@ -88,19 +99,28 @@ int main(int argc, char **argv)
8899
scan_msg.range_max = 20.0;
89100
scan_msg.scan_time = 100.0 / cfg.scaningFrequency;
90101
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;
102+
103+
const double output_range_start_angle = static_cast<double>(outputRange.startAngle) / 10000.0 * DEG2RAD - M_PI / 2.0;
104+
const double output_range_stop_angle = static_cast<double>(outputRange.stopAngle) / 10000.0 * DEG2RAD - M_PI / 2.0;
105+
angle_max = std::min(output_range_stop_angle, angle_max);
106+
angle_min = std::max(output_range_start_angle, angle_min);
107+
108+
scan_msg.angle_min = angle_min;
109+
scan_msg.angle_max = angle_max;
93110

94111
ROS_DEBUG_STREAM("Device resolution is " << (double)outputRange.angleResolution / 10000.0 << " degrees.");
95112
ROS_DEBUG_STREAM("Device frequency is " << (double)cfg.scaningFrequency / 100.0 << " Hz");
96113

97-
int angle_range = outputRange.stopAngle - outputRange.startAngle;
98-
int num_values = angle_range / outputRange.angleResolution ;
99-
if (angle_range % outputRange.angleResolution == 0)
100-
{
101-
// Include endpoint
102-
++num_values;
103-
}
114+
const double angle_resolution = static_cast<double>(outputRange.angleResolution) / 10000.0 * DEG2RAD;
115+
const double angle_range = angle_max - angle_min;
116+
int num_values = std::floor(angle_range / angle_resolution) + 1;
117+
118+
// Determine start index for incoming data
119+
const int start_idx = std::ceil((angle_min - output_range_start_angle) / angle_resolution);
120+
121+
ROS_DEBUG_STREAM("Number of ranges is " << num_values);
122+
ROS_DEBUG_STREAM("Range start index is " << start_idx);
123+
104124
scan_msg.ranges.resize(num_values);
105125
scan_msg.intensities.resize(num_values);
106126

@@ -176,14 +196,15 @@ int main(int argc, char **argv)
176196
ROS_DEBUG("Reading scan data.");
177197
if (laser.getScanData(&data))
178198
{
179-
for (int i = 0; i < data.dist_len1; i++)
180-
{
181-
scan_msg.ranges[i] = data.dist1[i] * 0.001;
182-
}
199+
ROS_ASSERT_MSG(data.dist_len1 == data.rssi_len1,
200+
"Number of ranges (%d) does not match number of intensities (%d)",
201+
data.dist_len1,
202+
data.rssi_len1);
183203

184-
for (int i = 0; i < data.rssi_len1; i++)
204+
for (int i = 0; i < num_values; i++)
185205
{
186-
scan_msg.intensities[i] = data.rssi1[i];
206+
scan_msg.ranges[i] = data.dist1[i + start_idx] * 0.001;
207+
scan_msg.intensities[i] = data.rssi1[i + start_idx];
187208
}
188209

189210
ROS_DEBUG("Publishing scan data.");

0 commit comments

Comments
 (0)