@@ -41,6 +41,8 @@ int main(int argc, char **argv)
41
41
sensor_msgs::LaserScan scan_msg;
42
42
43
43
// parameters
44
+ double angle_max;
45
+ double angle_min;
44
46
std::string host;
45
47
std::string frame_id;
46
48
bool inf_range;
@@ -51,11 +53,20 @@ int main(int argc, char **argv)
51
53
ros::NodeHandle n (" ~" );
52
54
ros::Publisher scan_pub = nh.advertise <sensor_msgs::LaserScan>(" scan" , 1 );
53
55
56
+ n.param <double >(" angle_max" , angle_max, M_PI);
57
+ n.param <double >(" angle_min" , angle_min, -M_PI);
54
58
n.param <std::string>(" host" , host, " 192.168.1.2" );
55
59
n.param <std::string>(" frame_id" , frame_id, " laser" );
56
60
n.param <bool >(" publish_min_range_as_inf" , inf_range, false );
57
61
n.param <int >(" port" , port, 2111 );
58
62
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
+
59
70
while (ros::ok ())
60
71
{
61
72
ROS_INFO_STREAM (" Connecting to laser at " << host);
@@ -92,19 +103,28 @@ int main(int argc, char **argv)
92
103
scan_msg.range_max = 20.0 ;
93
104
scan_msg.scan_time = 100.0 / cfg.scaningFrequency ;
94
105
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;
97
114
98
115
ROS_DEBUG_STREAM (" Device resolution is " << (double )outputRange.angleResolution / 10000.0 << " degrees." );
99
116
ROS_DEBUG_STREAM (" Device frequency is " << (double )cfg.scaningFrequency / 100.0 << " Hz" );
100
117
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
+
108
128
scan_msg.ranges .resize (num_values);
109
129
scan_msg.intensities .resize (num_values);
110
130
@@ -180,9 +200,14 @@ int main(int argc, char **argv)
180
200
ROS_DEBUG (" Reading scan data." );
181
201
if (laser.getScanData (&data))
182
202
{
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++)
184
209
{
185
- float range_data = data.dist1 [i] * 0.001 ;
210
+ const float range_data = data.dist1 [i + start_idx ] * 0.001 ;
186
211
187
212
if (inf_range && range_data < scan_msg.range_min )
188
213
{
@@ -192,11 +217,9 @@ int main(int argc, char **argv)
192
217
{
193
218
scan_msg.ranges [i] = range_data;
194
219
}
195
- }
196
220
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];
200
223
}
201
224
202
225
ROS_DEBUG (" Publishing scan data." );
0 commit comments