mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 23:55:09 +00:00
66 lines
2.0 KiB
Plaintext
66 lines
2.0 KiB
Plaintext
|
<?xml version="1.0"?>
|
||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||
|
|
||
|
<joint name="laser_joint" type="fixed">
|
||
|
<parent link="chassis"/>
|
||
|
<child link="laser_frame"/>
|
||
|
<origin xyz="0.122 0 0.212" rpy="0 0 0"/>
|
||
|
</joint>
|
||
|
|
||
|
<link name="laser_frame">
|
||
|
<visual>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.05" length="0.04"/>
|
||
|
</geometry>
|
||
|
<material name="black"/>
|
||
|
</visual>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 -0.05"/>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.01" length="0.1"/>
|
||
|
</geometry>
|
||
|
<material name="black"/>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.05" length="0.04"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05">
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
</xacro:inertial_cylinder>
|
||
|
</link>
|
||
|
|
||
|
|
||
|
|
||
|
<gazebo reference="laser_frame">
|
||
|
<material>Gazebo/Black</material>
|
||
|
|
||
|
<sensor name="laser" type="ray">
|
||
|
<pose> 0 0 0 0 0 0 </pose>
|
||
|
<visualize>false</visualize>
|
||
|
<update_rate>10</update_rate>
|
||
|
<ray>
|
||
|
<scan>
|
||
|
<horizontal>
|
||
|
<samples>360</samples>
|
||
|
<min_angle>-3.14</min_angle>
|
||
|
<max_angle>3.14</max_angle>
|
||
|
</horizontal>
|
||
|
</scan>
|
||
|
<range>
|
||
|
<min>0.3</min>
|
||
|
<max>12</max>
|
||
|
</range>
|
||
|
</ray>
|
||
|
<plugin name="laser_controller" filename="libgazebo_ros_ray_sensor.so">
|
||
|
<ros>
|
||
|
<argument>~/out:=scan</argument>
|
||
|
</ros>
|
||
|
<output_type>sensor_msgs/LaserScan</output_type>
|
||
|
<frame_name>laser_frame</frame_name>
|
||
|
</plugin>
|
||
|
</sensor>
|
||
|
</gazebo>
|
||
|
|
||
|
</robot>
|