48 lines
1.7 KiB
Plaintext
48 lines
1.7 KiB
Plaintext
|
<?xml version="1.0"?>
|
||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||
|
|
||
|
<xacro:property name="camera_length" value="0.01"/>
|
||
|
<xacro:property name="camera_width" value="0.1"/>
|
||
|
<xacro:property name="camera_height" value="0.05"/>
|
||
|
|
||
|
|
||
|
<link name="camera_link">
|
||
|
<visual>
|
||
|
<geometry>
|
||
|
<box size="${camera_length} ${camera_width} ${camera_height}"/>
|
||
|
</geometry>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<material name="gray" />
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<geometry>
|
||
|
<box size="${camera_length} ${camera_width} ${camera_height}"/>
|
||
|
</geometry>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
</collision>
|
||
|
<xacro:box_inertia m="0.1" l="${camera_length}" w="${camera_width}" h="${camera_height}" xyz="0 0 0" rpy="0 0 0"/>
|
||
|
</link>
|
||
|
|
||
|
<joint name="base_camera_joint" type="fixed">
|
||
|
<parent link="base_link"/>
|
||
|
<child link="camera_link"/>
|
||
|
<origin xyz="${(base_length + camera_length)/ 2} 0 ${base_height/2}" rpy="0 0 0"/>
|
||
|
</joint>
|
||
|
|
||
|
<gazebo reference="camera_link">
|
||
|
<material>Gazebo/Red</material>
|
||
|
<sensor name="camera_sensor" type="camera">
|
||
|
<!-- x y z r p y-->
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<!-- whether you can see projection in gazebo or not-->
|
||
|
<visualize>true</visualize>
|
||
|
<!-- update rate in hz-->
|
||
|
<update_rate>10.0</update_rate>
|
||
|
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||
|
<!-- camera link -->
|
||
|
<frame_name>camera_link</frame_name>
|
||
|
</plugin>
|
||
|
</sensor>
|
||
|
</gazebo>
|
||
|
|
||
|
</robot>
|