Files
simulation/models/custom_ugv/model.sdf
2026-02-09 03:39:49 +00:00

160 lines
5.3 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.6">
<model name="custom_ugv">
<static>false</static>
<link name="base_link">
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass>5.0</mass>
<inertia>
<ixx>0.1</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.15</iyy><iyz>0</iyz><izz>0.1</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry><box><size>0.4 0.3 0.15</size></box></geometry>
</collision>
<visual name="visual">
<geometry><box><size>0.4 0.3 0.15</size></box></geometry>
<material><ambient>0.3 0.3 0.8 1</ambient></material>
</visual>
</link>
<link name="left_wheel">
<pose>0 0.175 0.05 -1.5708 0 0</pose>
<inertial>
<mass>0.5</mass>
<inertia>
<ixx>0.001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.001</iyy><iyz>0</iyz><izz>0.001</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry><cylinder><radius>0.05</radius><length>0.04</length></cylinder></geometry>
<surface>
<friction><ode><mu>1.0</mu><mu2>1.0</mu2></ode></friction>
</surface>
</collision>
<visual name="visual">
<geometry><cylinder><radius>0.05</radius><length>0.04</length></cylinder></geometry>
<material><ambient>0.1 0.1 0.1 1</ambient></material>
</visual>
</link>
<link name="right_wheel">
<pose>0 -0.175 0.05 -1.5708 0 0</pose>
<inertial>
<mass>0.5</mass>
<inertia>
<ixx>0.001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.001</iyy><iyz>0</iyz><izz>0.001</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry><cylinder><radius>0.05</radius><length>0.04</length></cylinder></geometry>
<surface>
<friction><ode><mu>1.0</mu><mu2>1.0</mu2></ode></friction>
</surface>
</collision>
<visual name="visual">
<geometry><cylinder><radius>0.05</radius><length>0.04</length></cylinder></geometry>
<material><ambient>0.1 0.1 0.1 1</ambient></material>
</visual>
</link>
<link name="caster">
<pose>-0.15 0 0.025 0 0 0</pose>
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>0.0001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.0001</iyy><iyz>0</iyz><izz>0.0001</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry><sphere><radius>0.025</radius></sphere></geometry>
<surface>
<friction><ode><mu>0.0</mu><mu2>0.0</mu2></ode></friction>
</surface>
</collision>
<visual name="visual">
<geometry><sphere><radius>0.025</radius></sphere></geometry>
<material><ambient>0.1 0.1 0.1 1</ambient></material>
</visual>
</link>
<joint name="left_wheel_joint" type="revolute">
<parent>base_link</parent>
<child>left_wheel</child>
<axis><xyz>0 0 1</xyz></axis>
</joint>
<joint name="right_wheel_joint" type="revolute">
<parent>base_link</parent>
<child>right_wheel</child>
<axis><xyz>0 0 1</xyz></axis>
</joint>
<joint name="caster_joint" type="ball">
<parent>base_link</parent>
<child>caster</child>
</joint>
<link name="camera_link">
<pose>0.22 0 0.15 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.00001</iyy><iyz>0</iyz><izz>0.00001</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry><box><size>0.02 0.04 0.02</size></box></geometry>
<material><ambient>0 0 0 1</ambient></material>
</visual>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.57</horizontal_fov>
<image><width>640</width><height>480</height><format>R8G8B8</format></image>
<clip><near>0.1</near><far>50</far></clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
<ros>
<namespace>/ugv</namespace>
<remapping>image_raw:=camera/forward/image_raw</remapping>
<remapping>camera_info:=camera/forward/camera_info</remapping>
</ros>
<camera_name>forward_camera</camera_name>
<frame_name>camera_link</frame_name>
</plugin>
</sensor>
</link>
<joint name="camera_joint" type="fixed">
<parent>base_link</parent>
<child>camera_link</child>
</joint>
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
<ros><namespace>/ugv</namespace></ros>
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.35</wheel_separation>
<wheel_diameter>0.1</wheel_diameter>
<max_wheel_torque>5</max_wheel_torque>
<max_wheel_acceleration>2.0</max_wheel_acceleration>
<command_topic>cmd_vel</command_topic>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
</plugin>
</model>
</sdf>