mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-27 09:25:47 +00:00
62 lines
1.8 KiB
XML
62 lines
1.8 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
|
|
|
<joint name="camera_joint" type="fixed">
|
|
<parent link="chassis"/>
|
|
<child link="camera_link"/>
|
|
<origin xyz="${chassis_length/2} 0 ${chassis_height/2}" rpy="0 0 0"/>
|
|
</joint>
|
|
|
|
<link name="camera_link">
|
|
<visual>
|
|
<geometry>
|
|
<box size="0.010 0.03 0.03"/>
|
|
</geometry>
|
|
<material name="black"/>
|
|
</visual>
|
|
<visual>
|
|
<origin xyz="0 0 -0.05"/>
|
|
<geometry>
|
|
<cylinder radius="0.002" length="0.1"/>
|
|
</geometry>
|
|
<material name="black"/>
|
|
</visual>
|
|
</link>
|
|
|
|
|
|
<joint name="camera_optical_joint" type="fixed">
|
|
<parent link="camera_link"/>
|
|
<child link="camera_link_optical"/>
|
|
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
|
</joint>
|
|
|
|
<link name="camera_link_optical"></link>
|
|
|
|
|
|
|
|
<gazebo reference="camera_link">
|
|
<material>Gazebo/Black</material>
|
|
|
|
<sensor name="camera" type="camera">
|
|
<pose> 0 0 0 0 0 0 </pose>
|
|
<visualize>true</visualize>
|
|
<update_rate>10</update_rate>
|
|
<camera>
|
|
<horizontal_fov>1.089</horizontal_fov>
|
|
<image>
|
|
<format>R8G8B8</format>
|
|
<width>640</width>
|
|
<height>480</height>
|
|
</image>
|
|
<clip>
|
|
<near>0.05</near>
|
|
<far>8.0</far>
|
|
</clip>
|
|
</camera>
|
|
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
|
<frame_name>camera_link_optical</frame_name>
|
|
</plugin>
|
|
</sensor>
|
|
</gazebo>
|
|
|
|
</robot> |