@@ -86,6 +86,30 @@ def __init__(self) -> None:
86
86
self .declare_parameter ('publish_clock' , True )
87
87
self .publish_clock = self .get_parameter ('publish_clock' ).get_parameter_value ().bool_value
88
88
89
+ self .declare_parameter ('scan_range_min' , 0.05 )
90
+ self .scan_range_min = \
91
+ self .get_parameter ('scan_range_min' ).get_parameter_value ().double_value
92
+
93
+ self .declare_parameter ('scan_range_max' , 30.0 )
94
+ self .scan_range_max = \
95
+ self .get_parameter ('scan_range_max' ).get_parameter_value ().double_value
96
+
97
+ self .declare_parameter ('scan_angle_min' , - math .pi )
98
+ self .scan_angle_min = \
99
+ self .get_parameter ('scan_angle_min' ).get_parameter_value ().double_value
100
+
101
+ self .declare_parameter ('scan_angle_max' , math .pi )
102
+ self .scan_angle_max = \
103
+ self .get_parameter ('scan_angle_max' ).get_parameter_value ().double_value
104
+
105
+ self .declare_parameter ('scan_angle_increment' , 0.0261 ) # 0.0261 rad = 1.5 degrees
106
+ self .scan_angle_increment = \
107
+ self .get_parameter ('scan_angle_increment' ).get_parameter_value ().double_value
108
+
109
+ self .declare_parameter ('scan_use_inf' , True )
110
+ self .use_inf = \
111
+ self .get_parameter ('scan_use_inf' ).get_parameter_value ().bool_value
112
+
89
113
self .t_map_to_odom = TransformStamped ()
90
114
self .t_map_to_odom .header .frame_id = self .map_frame_id
91
115
self .t_map_to_odom .child_frame_id = self .odom_frame_id
@@ -235,14 +259,14 @@ def publishLaserScan(self) -> None:
235
259
self .scan_msg = LaserScan ()
236
260
self .scan_msg .header .stamp = (self .get_clock ().now ()).to_msg ()
237
261
self .scan_msg .header .frame_id = self .scan_frame_id
238
- self .scan_msg .angle_min = - math . pi
239
- self .scan_msg .angle_max = math . pi
262
+ self .scan_msg .angle_min = self . scan_angle_min
263
+ self .scan_msg .angle_max = self . scan_angle_max
240
264
# 1.5 degrees
241
- self .scan_msg .angle_increment = 0.0261799
265
+ self .scan_msg .angle_increment = self . scan_angle_increment
242
266
self .scan_msg .time_increment = 0.0
243
267
self .scan_msg .scan_time = 0.1
244
- self .scan_msg .range_min = 0.05
245
- self .scan_msg .range_max = 30.0
268
+ self .scan_msg .range_min = self . scan_range_min
269
+ self .scan_msg .range_max = self . scan_range_max
246
270
num_samples = int (
247
271
(self .scan_msg .angle_max - self .scan_msg .angle_min ) /
248
272
self .scan_msg .angle_increment )
@@ -323,7 +347,10 @@ def getLaserPose(self) -> tuple[float, float, float]:
323
347
324
348
def getLaserScan (self , num_samples : int ) -> None :
325
349
if self .map is None or self .initial_pose is None or self .mat_base_to_laser is None :
326
- self .scan_msg .ranges = [self .scan_msg .range_max - 0.1 ] * num_samples
350
+ if self .use_inf :
351
+ self .scan_msg .ranges = [float ('inf' )] * num_samples
352
+ else :
353
+ self .scan_msg .ranges = [self .scan_msg .range_max - 0.1 ] * num_samples
327
354
return
328
355
329
356
x0 , y0 , theta = self .getLaserPose ()
@@ -332,7 +359,10 @@ def getLaserScan(self, num_samples: int) -> None:
332
359
333
360
if not 0 < mx0 < self .map .info .width or not 0 < my0 < self .map .info .height :
334
361
# outside map
335
- self .scan_msg .ranges = [self .scan_msg .range_max - 0.1 ] * num_samples
362
+ if self .use_inf :
363
+ self .scan_msg .ranges = [float ('inf' )] * num_samples
364
+ else :
365
+ self .scan_msg .ranges = [self .scan_msg .range_max - 0.1 ] * num_samples
336
366
return
337
367
338
368
for i in range (num_samples ):
@@ -361,6 +391,8 @@ def getLaserScan(self, num_samples: int) -> None:
361
391
break
362
392
363
393
line_iterator .advance ()
394
+ if self .scan_msg .ranges [i ] == 0.0 and self .use_inf :
395
+ self .scan_msg .ranges [i ] = float ('inf' )
364
396
365
397
366
398
def main () -> None :
0 commit comments