Skip to content

Commit

Permalink
Limit the simulated RP Lidar to 180 degrees (the max supported by the…
Browse files Browse the repository at this point in the history
… plugin)
  • Loading branch information
civerachb-cpr committed Jul 30, 2024
1 parent c0df707 commit b6f30a2
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion turtlebot4_description/urdf/sensors/rplidar.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,12 @@
</link>

<gazebo reference="${name}_link">
<!--
GPU Ray sensor plugin only supports 180 degrees, so limig to the front arc only
-->
<xacro:ray_sensor sensor_name="${name}" gazebo="${gazebo}"
update_rate="62.0" visualize="1"
h_samples="640" h_res="1.0" h_min_angle="${-pi}" h_max_angle="${pi}"
h_samples="640" h_res="1.0" h_min_angle="${-pi/2}" h_max_angle="${pi/2}"
r_min="0.164" r_max="12.0" r_res="0.01">
<plugin name="dummy" filename="dummyfile"></plugin>
</xacro:ray_sensor>
Expand Down

0 comments on commit b6f30a2

Please sign in to comment.