@@ -88,6 +88,30 @@ def __init__(self):
8888 self .declare_parameter ('publish_clock' , True )
8989 self .publish_clock = self .get_parameter ('publish_clock' ).get_parameter_value ().bool_value
9090
91+ self .declare_parameter ('scan_range_min' , 0.05 )
92+ self .scan_range_min = \
93+ self .get_parameter ('scan_range_min' ).get_parameter_value ().double_value
94+
95+ self .declare_parameter ('scan_range_max' , 30.0 )
96+ self .scan_range_max = \
97+ self .get_parameter ('scan_range_max' ).get_parameter_value ().double_value
98+
99+ self .declare_parameter ('scan_angle_min' , - math .pi )
100+ self .scan_angle_min = \
101+ self .get_parameter ('scan_angle_min' ).get_parameter_value ().double_value
102+
103+ self .declare_parameter ('scan_angle_max' , math .pi )
104+ self .scan_angle_max = \
105+ self .get_parameter ('scan_angle_max' ).get_parameter_value ().double_value
106+
107+ self .declare_parameter ('scan_angle_increment' , 0.0261 ) # 0.0261 rad = 1.5 degrees
108+ self .scan_angle_increment = \
109+ self .get_parameter ('scan_angle_increment' ).get_parameter_value ().double_value
110+
111+ self .declare_parameter ('scan_use_inf' , True )
112+ self .use_inf = \
113+ self .get_parameter ('scan_use_inf' ).get_parameter_value ().bool_value
114+
91115 self .t_map_to_odom = TransformStamped ()
92116 self .t_map_to_odom .header .frame_id = self .map_frame_id
93117 self .t_map_to_odom .child_frame_id = self .odom_frame_id
@@ -237,14 +261,14 @@ def publishLaserScan(self):
237261 self .scan_msg = LaserScan ()
238262 self .scan_msg .header .stamp = (self .get_clock ().now ()).to_msg ()
239263 self .scan_msg .header .frame_id = self .scan_frame_id
240- self .scan_msg .angle_min = - math . pi
241- self .scan_msg .angle_max = math . pi
264+ self .scan_msg .angle_min = self . scan_angle_min
265+ self .scan_msg .angle_max = self . scan_angle_max
242266 # 1.5 degrees
243- self .scan_msg .angle_increment = 0.0261799
267+ self .scan_msg .angle_increment = self . scan_angle_increment
244268 self .scan_msg .time_increment = 0.0
245269 self .scan_msg .scan_time = 0.1
246- self .scan_msg .range_min = 0.05
247- self .scan_msg .range_max = 30.0
270+ self .scan_msg .range_min = self . scan_range_min
271+ self .scan_msg .range_max = self . scan_range_max
248272 num_samples = int (
249273 (self .scan_msg .angle_max - self .scan_msg .angle_min ) /
250274 self .scan_msg .angle_increment )
@@ -323,7 +347,10 @@ def getLaserPose(self):
323347
324348 def getLaserScan (self , num_samples ):
325349 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
327354 return
328355
329356 x0 , y0 , theta = self .getLaserPose ()
@@ -332,7 +359,10 @@ def getLaserScan(self, num_samples):
332359
333360 if not 0 < mx0 < self .map .info .width or not 0 < my0 < self .map .info .height :
334361 # 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
336366 return
337367
338368 for i in range (num_samples ):
@@ -361,6 +391,8 @@ def getLaserScan(self, num_samples):
361391 break
362392
363393 line_iterator .advance ()
394+ if self .scan_msg .ranges [i ] == 0.0 and self .use_inf :
395+ self .scan_msg .ranges [i ] = float ('inf' )
364396
365397
366398def main ():
0 commit comments