course2_ws/my_robot1_description/urdf_his/camera.xacro

54 lines
1.9 KiB
Plaintext
Raw Permalink Normal View History

2024-12-19 00:49:29 +00:00
<?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>
<material name="grey" />
</visual>
<collision>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
</geometry>
</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} 0 ${base_height / 2.0}" rpy="0 0 0" />
</joint>
<link name="camera_link_optical">
</link>
<joint name="camera_optical_joint" type="fixed">
<!-- these values have to be these values otherwise the gazebo camera
image won't be aligned properly with the frame it is supposedly
originating from -->
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
<parent link="camera_link"/>
<child link="camera_link_optical"/>
</joint>
<gazebo reference="camera_link">
<material>Gazebo/Red</material>
<sensor name="camera_sensor" type="camera">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>10.0</update_rate>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<frame_name>camera_link_optical</frame_name>
</plugin>
</sensor>
</gazebo>
</robot>