Skip to content

Commit

Permalink
Merge branch 'ros2-add-launch-and-remappings' into ros2-add-ur-component
Browse files Browse the repository at this point in the history
  • Loading branch information
delihus committed May 8, 2024
2 parents 7c21b00 + 442e5ba commit a38d56e
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 39 deletions.
4 changes: 2 additions & 2 deletions launch/gz_components.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@ def get_launch_description(name: str, package: str, namespace: str, component: y
device_namespace = get_value(component, "device_namespace")
robot_namespace = namespace

if robot_namespace[0] != "/":
if len(robot_namespace) and robot_namespace[0] != "/":
robot_namespace = "/" + robot_namespace
if device_namespace[0] != "/":
if len(device_namespace) and device_namespace[0] != "/":
device_namespace = "/" + device_namespace

return IncludeLaunchDescription(
Expand Down
73 changes: 36 additions & 37 deletions urdf/slamtec_rplidar_s3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -65,44 +65,43 @@

<link name="${prefix}laser" />

<xacro:if value="${simulation_engine == 'ignition-gazebo'}">
<gazebo reference="${prefix}laser">
<!-- gpu_lidar has to be set, CPU lidar doesn't work in ignition -
https://github.com/gazebosim/gz-sensors/issues/26 -->
<sensor type="gpu_lidar" name="${ns}${prefix}rplidar_s3_sensor">
<gazebo reference="${prefix}laser">
<!-- gpu_lidar has to be set, CPU lidar doesn't work in ignition -
https://github.com/gazebosim/gz-sensors/issues/26 -->
<sensor type="gpu_lidar" name="${ns}${prefix}rplidar_s3_sensor">

<topic>${ns}${device_ns}scan</topic>
<frame_id>${ns}${prefix}laser</frame_id>
<ignition_frame_id>${ns}${prefix}laser</ignition_frame_id>
<topic>${ns}${device_ns}scan</topic>
<frame_id>${ns}${prefix}laser</frame_id>
<ignition_frame_id>${ns}${prefix}laser</ignition_frame_id>

<update_rate>10.0</update_rate>
<ray>
<scan>
<horizontal>
<samples>3000</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>40.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.03</stddev>
</noise>
</ray>
<always_on>1</always_on>
<visualize>false</visualize>
<ros>
<namespace>${ns}${device_ns}</namespace>
</ros>
</sensor>
</gazebo>

<update_rate>10.0</update_rate>
<ray>
<scan>
<horizontal>
<samples>3000</samples>
<resolution>1</resolution>
<min_angle>-${pi}</min_angle>
<max_angle>${pi}</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>40.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.03</stddev>
</noise>
</ray>
<always_on>1</always_on>
<visualize>false</visualize>
<ros>
<namespace>${ns}${device_ns}</namespace>
</ros>
</sensor>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>

0 comments on commit a38d56e

Please sign in to comment.