Skip to content

Commit cb4e909

Browse files
authored
feat: add max_angle and min_angle to 2d and 3d lidar models (#69)
1 parent ef38ecf commit cb4e909

19 files changed

+93
-39
lines changed

robotnik_sensors/CHANGELOG.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,10 @@
22
Changelog for package robotnik_sensors
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
Unreleased
6+
----------
7+
* Add min_angle and max_angle to define angle limits for 2d and 3d laser in simulation
8+
59
2.1.0 (2025-09-11)
610
------------------
711
* BRAKING_CHANGE: removed `gazebo_classic` parameter for sensor macros

robotnik_sensors/urdf/2d_lidar/hokuyo_urg04lx.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=hokuyo_urg04lx
1515
node_namespace:=${None}
16+
min_angle:=-2.0943
17+
max_angle:=2.0943
1618
topic_prefix:=~/">
1719
<!-- node_namespace is used from node_name if not set -->
1820
<xacro:if value="${node_namespace == None}">
@@ -71,8 +73,8 @@
7173
gazebo_ignition="${gazebo_ignition}"
7274
min_range="0.06"
7375
max_range="4.0"
74-
min_angle="-2.0943"
75-
max_angle="2.0943"
76+
min_angle="${min_angle}"
77+
max_angle="${max_angle}"
7678
frame_link="${frame_prefix}link"
7779
rate="10"
7880
resolution="0.004359297"

robotnik_sensors/urdf/2d_lidar/hokuyo_ust10lx.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=hokuyo_ust10lx
1515
node_namespace:=${None}
16+
min_angle:=-2.35
17+
max_angle:=2.35
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -82,8 +84,8 @@
8284
gazebo_ignition="${gazebo_ignition}"
8385
min_range="0.06"
8486
max_range="10.0"
85-
min_angle="-2.3562"
86-
max_angle="2.3562"
87+
min_angle="${min_angle}"
88+
max_angle="${max_angle}"
8789
frame_link="${frame_prefix}link"
8890
rate="40"
8991
resolution="0.004359297"

robotnik_sensors/urdf/2d_lidar/hokuyo_ust20lx.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=hokuyo_ust20lx
1515
node_namespace:=${None}
16+
min_angle:=-2.3562
17+
max_angle:=2.3562
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -82,8 +84,8 @@
8284
gazebo_ignition="${gazebo_ignition}"
8385
min_range="0.06"
8486
max_range="20.0"
85-
min_angle="-2.3562"
86-
max_angle="2.3562"
87+
min_angle="${min_angle}"
88+
max_angle="${max_angle}"
8789
frame_link="${frame_prefix}link"
8890
rate="40"
8991
resolution="0.004359297"

robotnik_sensors/urdf/2d_lidar/hokuyo_utm30lx.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=hokuyo_utm30lx
1515
node_namespace:=${None}
16+
min_angle:=-2.35
17+
max_angle:=2.35
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -77,8 +79,8 @@
7779
gazebo_ignition="${gazebo_ignition}"
7880
min_range="0.10"
7981
max_range="30.0"
80-
min_angle="-2.35"
81-
max_angle="2.35"
82+
min_angle="${min_angle}"
83+
max_angle="${max_angle}"
8284
frame_link="${frame_prefix}link"
8385
rate="30"
8486
resolution="0.01"

robotnik_sensors/urdf/2d_lidar/sick_microscan3.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=sick_microscan3
1515
node_namespace:=${None}
16+
min_angle:=-2.35
17+
max_angle:=2.35
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -81,8 +83,8 @@
8183
gazebo_ignition="${gazebo_ignition}"
8284
min_range="0.05"
8385
max_range="64.0"
84-
min_angle="-2.35"
85-
max_angle="2.35"
86+
min_angle="${min_angle}"
87+
max_angle="${max_angle}"
8688
frame_link="${frame_prefix}link"
8789
rate="30"
8890
resolution="0.00575"

robotnik_sensors/urdf/2d_lidar/sick_nanoscan3.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=sick_nanoscan3
1515
node_namespace:=${None}
16+
min_angle:=-2.35
17+
max_angle:=2.35
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -81,8 +83,8 @@
8183
gazebo_ignition="${gazebo_ignition}"
8284
min_range="0.05"
8385
max_range="40.0"
84-
min_angle="${-radians(135)}"
85-
max_angle="${radians(135)}"
86+
min_angle="${min_angle}"
87+
max_angle="${max_angle}"
8688
frame_link="${frame_prefix}link"
8789
rate="12.5"
8890
resolution="0.00575"

robotnik_sensors/urdf/2d_lidar/sick_outdoorscan3.urdf.xacro

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=sick_outdoorscan3
1515
node_namespace:=${None}
16+
min_angle:=-2.35
17+
max_angle:=2.35
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->

robotnik_sensors/urdf/2d_lidar/sick_s300.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=sick_s300
1515
node_namespace:=${None}
16+
min_angle:=-2.35
17+
max_angle:=2.35
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -80,8 +82,8 @@
8082
gazebo_ignition="${gazebo_ignition}"
8183
min_range="0.05"
8284
max_range="10.0"
83-
min_angle="${-radians(130)}"
84-
max_angle="${radians(130)}"
85+
min_angle="${min_angle}"
86+
max_angle="${max_angle}"
8587
frame_link="${frame_prefix}link"
8688
rate="25.0"
8789
resolution="0.00575"

robotnik_sensors/urdf/2d_lidar/sick_s3000.urdf.xacro

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
gazebo_ignition:=false
1414
node_name:=sick_s3000
1515
node_namespace:=${None}
16+
min_angle:=-1.62316
17+
max_angle:=1.62316
1618
topic_prefix:=~/
1719
gpu:=false">
1820
<!-- node_namespace is used from node_name if not set -->
@@ -80,8 +82,8 @@
8082
gazebo_ignition="${gazebo_ignition}"
8183
min_range="0.07"
8284
max_range="49.0"
83-
min_angle="${-radians(93)}"
84-
max_angle="${radians(93)}"
85+
min_angle="${min_angle}"
86+
max_angle="${max_angle}"
8587
frame_link="${frame_prefix}link"
8688
rate="15.0"
8789
resolution="0.00575"

0 commit comments

Comments
 (0)