Skip to content

Commit 786ec09

Browse files
Jacob Perronjacobperron
authored andcommitted
Add parameters for min/max angle
1 parent dc844b4 commit 786ec09

File tree

1 file changed

+38
-15
lines changed

1 file changed

+38
-15
lines changed

src/LMS1xx_node.cpp

Lines changed: 38 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,8 @@ int main(int argc, char **argv)
4141
sensor_msgs::LaserScan scan_msg;
4242

4343
// parameters
44+
double angle_max;
45+
double angle_min;
4446
std::string host;
4547
std::string frame_id;
4648
bool inf_range;
@@ -51,11 +53,20 @@ int main(int argc, char **argv)
5153
ros::NodeHandle n("~");
5254
ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
5355

56+
n.param<double>("angle_max", angle_max, M_PI);
57+
n.param<double>("angle_min", angle_min, -M_PI);
5458
n.param<std::string>("host", host, "192.168.1.2");
5559
n.param<std::string>("frame_id", frame_id, "laser");
5660
n.param<bool>("publish_min_range_as_inf", inf_range, false);
5761
n.param<int>("port", port, 2111);
5862

63+
if (angle_min > angle_max)
64+
{
65+
ROS_FATAL("Minimum angle %f exceeds maximum angle %f", angle_min, angle_max);
66+
ros::shutdown();
67+
return 1;
68+
}
69+
5970
while (ros::ok())
6071
{
6172
ROS_INFO_STREAM("Connecting to laser at " << host);
@@ -92,19 +103,28 @@ int main(int argc, char **argv)
92103
scan_msg.range_max = 20.0;
93104
scan_msg.scan_time = 100.0 / cfg.scaningFrequency;
94105
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);
106+
107+
const double output_range_start_angle = static_cast<double>(outputRange.startAngle) / 10000.0 * DEG2RAD - M_PI / 2.0;
108+
const double output_range_stop_angle = static_cast<double>(outputRange.stopAngle) / 10000.0 * DEG2RAD - M_PI / 2.0;
109+
angle_max = std::min(output_range_stop_angle, angle_max);
110+
angle_min = std::max(output_range_start_angle, angle_min);
111+
112+
scan_msg.angle_min = angle_min;
113+
scan_msg.angle_max = angle_max;
97114

98115
ROS_DEBUG_STREAM("Device resolution is " << (double)outputRange.angleResolution / 10000.0 << " degrees.");
99116
ROS_DEBUG_STREAM("Device frequency is " << (double)cfg.scaningFrequency / 100.0 << " Hz");
100117

101-
int angle_range = outputRange.stopAngle - outputRange.startAngle;
102-
int num_values = angle_range / outputRange.angleResolution;
103-
if (angle_range % outputRange.angleResolution == 0)
104-
{
105-
// Include endpoint
106-
++num_values;
107-
}
118+
const double angle_resolution = static_cast<double>(outputRange.angleResolution) / 10000.0 * DEG2RAD;
119+
const double angle_range = angle_max - angle_min;
120+
int num_values = round(angle_range / angle_resolution) + 1;
121+
122+
// Determine start index for incoming data
123+
const int start_idx = std::ceil((angle_min - output_range_start_angle) / angle_resolution);
124+
125+
ROS_DEBUG_STREAM("Number of ranges is " << num_values);
126+
ROS_DEBUG_STREAM("Range start index is " << start_idx);
127+
108128
scan_msg.ranges.resize(num_values);
109129
scan_msg.intensities.resize(num_values);
110130

@@ -180,9 +200,14 @@ int main(int argc, char **argv)
180200
ROS_DEBUG("Reading scan data.");
181201
if (laser.getScanData(&data))
182202
{
183-
for (int i = 0; i < data.dist_len1; i++)
203+
ROS_ASSERT_MSG(data.dist_len1 == data.rssi_len1,
204+
"Number of ranges (%d) does not match number of intensities (%d)",
205+
data.dist_len1,
206+
data.rssi_len1);
207+
208+
for (int i = 0; i < num_values; i++)
184209
{
185-
float range_data = data.dist1[i] * 0.001;
210+
const float range_data = data.dist1[i + start_idx] * 0.001;
186211

187212
if (inf_range && range_data < scan_msg.range_min)
188213
{
@@ -192,11 +217,9 @@ int main(int argc, char **argv)
192217
{
193218
scan_msg.ranges[i] = range_data;
194219
}
195-
}
196220

197-
for (int i = 0; i < data.rssi_len1; i++)
198-
{
199-
scan_msg.intensities[i] = data.rssi1[i];
221+
222+
scan_msg.intensities[i] = data.rssi1[i + start_idx];
200223
}
201224

202225
ROS_DEBUG("Publishing scan data.");

0 commit comments

Comments
 (0)