54ed5c6a82
Makes it easier to work on an individual part in isolation. Also change the vscode devconsole visualiser to one that works with includes
84 lines
3.4 KiB
XML
84 lines
3.4 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
<!-- ─────────────────────────────────────────────────────────────────────
|
|
Camera module
|
|
|
|
Mounted on camera_tilt_link (output of the tilt joint in pan_tilt.xacro).
|
|
|
|
Two frames are defined:
|
|
camera_link — physical body of the camera module
|
|
camera_optical_frame — REP-103 optical frame (Z forward, X right, Y down)
|
|
used as the sensor origin in Gazebo and ROS image topics
|
|
───────────────────────────────────────────────────────────────────── -->
|
|
|
|
<!-- Physical camera body — visual only, small box representing the module -->
|
|
<link name="camera_link">
|
|
<visual>
|
|
<geometry><box size="0.025 0.06 0.02"/></geometry>
|
|
<material name="blue"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry><box size="0.025 0.06 0.02"/></geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.03"/>
|
|
<inertia ixx="0.000005" ixy="0" ixz="0"
|
|
iyy="0.000005" iyz="0" izz="0.000005"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="camera_joint" type="fixed">
|
|
<parent link="camera_tilt_link"/>
|
|
<child link="camera_link"/>
|
|
<origin xyz="0.01 0 0" rpy="0 0 0"/>
|
|
</joint>
|
|
|
|
<!-- REP-103 optical frame: Z forward, X right, Y down.
|
|
The rpy="-pi/2 0 -pi/2" rotation maps the body frame (X-fwd, Y-left, Z-up)
|
|
to the optical frame convention expected by image_geometry and cv_bridge. -->
|
|
<link name="camera_optical_frame"/>
|
|
|
|
<joint name="camera_optical_joint" type="fixed">
|
|
<parent link="camera_link"/>
|
|
<child link="camera_optical_frame"/>
|
|
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
|
</joint>
|
|
|
|
<!-- ─────────────────────────────────────────────────────────────────────
|
|
Gazebo camera sensor (Gazebo Harmonic / gz-sim)
|
|
|
|
Image data is published on gz topics and bridged to ROS 2 via
|
|
ros_gz_bridge:
|
|
/camera/image (gz) → /camera/image_raw (ROS 2)
|
|
/camera/info (gz) → /camera/camera_info (ROS 2)
|
|
───────────────────────────────────────────────────────────────────── -->
|
|
<gazebo reference="camera_link">
|
|
<sensor name="camera" type="camera">
|
|
<always_on>1</always_on>
|
|
<update_rate>30</update_rate>
|
|
<visualize>true</visualize>
|
|
<camera>
|
|
<horizontal_fov>${camera_fov}</horizontal_fov>
|
|
<image>
|
|
<width>${camera_width}</width>
|
|
<height>${camera_height}</height>
|
|
<format>R8G8B8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.05</near>
|
|
<far>50.0</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
<!-- Publishes to gz topic /camera/image -->
|
|
<topic>/camera/image</topic>
|
|
</sensor>
|
|
</gazebo>
|
|
|
|
</robot>
|