|
|
@ -1,5 +1,7 @@ |
|
|
|
<?xml version="1.0"?> |
|
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_description"> |
|
|
|
<xacro:arg name="gpu_lidar" default="false" /> |
|
|
|
|
|
|
|
<xacro:include filename="$(find stretch_description)/urdf/stretch_main.xacro" /> |
|
|
|
<xacro:include filename="$(find stretch_description)/urdf/stretch_aruco.xacro" /> |
|
|
|
<xacro:include filename="$(find stretch_description)/urdf/stretch_d435i.xacro" /> |
|
|
@ -237,39 +239,77 @@ |
|
|
|
<material>Gazebo/Green</material> |
|
|
|
</gazebo> |
|
|
|
|
|
|
|
<!-- LIDAR --> |
|
|
|
<gazebo reference="laser"> |
|
|
|
<material>Gazebo/Black</material> |
|
|
|
<sensor type="gpu_ray" name="laser_sensor"> |
|
|
|
<pose>0 0 0 0 0 0</pose> |
|
|
|
<visualize>false</visualize> |
|
|
|
<update_rate>5.5</update_rate> |
|
|
|
<ray> |
|
|
|
<scan> |
|
|
|
<horizontal> |
|
|
|
<samples>2000</samples> |
|
|
|
<resolution>1</resolution> |
|
|
|
<min_angle>${-M_PI}</min_angle> |
|
|
|
<max_angle>${M_PI}</max_angle> |
|
|
|
</horizontal> |
|
|
|
</scan> |
|
|
|
<range> |
|
|
|
<min>0.08</min> |
|
|
|
<max>12.0</max> |
|
|
|
<resolution>0.01</resolution> |
|
|
|
</range> |
|
|
|
<noise> |
|
|
|
<type>gaussian</type> |
|
|
|
<mean>0.0</mean> |
|
|
|
<stddev>0.001</stddev> |
|
|
|
</noise> |
|
|
|
</ray> |
|
|
|
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_gpu_laser.so"> |
|
|
|
<topicName>scan</topicName> |
|
|
|
<frameName>laser</frameName> |
|
|
|
</plugin> |
|
|
|
</sensor> |
|
|
|
</gazebo> |
|
|
|
<!-- Non GPU LIDAR --> |
|
|
|
<xacro:unless value="$(arg gpu_lidar)"> |
|
|
|
<gazebo reference="laser"> |
|
|
|
<material>Gazebo/Black</material> |
|
|
|
<sensor type="ray" name="laser_sensor"> |
|
|
|
<pose>0 0 0 0 0 0</pose> |
|
|
|
<visualize>true</visualize> |
|
|
|
<update_rate>5.5</update_rate> |
|
|
|
<ray> |
|
|
|
<scan> |
|
|
|
<horizontal> |
|
|
|
<samples>2000</samples> |
|
|
|
<resolution>1</resolution> |
|
|
|
<min_angle>${-M_PI}</min_angle> |
|
|
|
<max_angle>${M_PI}</max_angle> |
|
|
|
</horizontal> |
|
|
|
</scan> |
|
|
|
<range> |
|
|
|
<min>0.08</min> |
|
|
|
<max>12.0</max> |
|
|
|
<resolution>0.01</resolution> |
|
|
|
</range> |
|
|
|
<noise> |
|
|
|
<type>gaussian</type> |
|
|
|
<mean>0.0</mean> |
|
|
|
<stddev>0.001</stddev> |
|
|
|
</noise> |
|
|
|
</ray> |
|
|
|
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_laser.so"> |
|
|
|
<topicName>scan</topicName> |
|
|
|
<frameName>laser</frameName> |
|
|
|
</plugin> |
|
|
|
</sensor> |
|
|
|
</gazebo> |
|
|
|
</xacro:unless> |
|
|
|
|
|
|
|
<!-- GPU LIDAR --> |
|
|
|
<xacro:if value="$(arg gpu_lidar)"> |
|
|
|
<gazebo reference="laser"> |
|
|
|
<material>Gazebo/Black</material> |
|
|
|
<sensor type="gpu_ray" name="laser_sensor"> |
|
|
|
<pose>0 0 0 0 0 0</pose> |
|
|
|
<visualize>true</visualize> |
|
|
|
<update_rate>5.5</update_rate> |
|
|
|
<ray> |
|
|
|
<scan> |
|
|
|
<horizontal> |
|
|
|
<samples>2000</samples> |
|
|
|
<resolution>1</resolution> |
|
|
|
<min_angle>${-M_PI}</min_angle> |
|
|
|
<max_angle>${M_PI}</max_angle> |
|
|
|
</horizontal> |
|
|
|
</scan> |
|
|
|
<range> |
|
|
|
<min>0.08</min> |
|
|
|
<max>12.0</max> |
|
|
|
<resolution>0.01</resolution> |
|
|
|
</range> |
|
|
|
<noise> |
|
|
|
<type>gaussian</type> |
|
|
|
<mean>0.0</mean> |
|
|
|
<stddev>0.001</stddev> |
|
|
|
</noise> |
|
|
|
</ray> |
|
|
|
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_gpu_laser.so"> |
|
|
|
<topicName>scan</topicName> |
|
|
|
<frameName>laser</frameName> |
|
|
|
</plugin> |
|
|
|
</sensor> |
|
|
|
</gazebo> |
|
|
|
</xacro:if> |
|
|
|
|
|
|
|
<!-- Base IMU --> |
|
|
|
<gazebo reference="base_link"> |
|
|
|