mirror of
https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git
synced 2025-09-15 13:08:35 +08:00
529 lines
14 KiB
XML
529 lines
14 KiB
XML
<?xml version="1.0" ?>
|
|
<sdf version="1.5">
|
|
<model name="turtlebot3_waffle">
|
|
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
|
|
|
|
<link name="base_footprint"/>
|
|
|
|
<link name="base_link">
|
|
|
|
<inertial>
|
|
<pose>-0.064 0 0.048 0 0 0</pose>
|
|
<inertia>
|
|
<ixx>0.001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.001</izz>
|
|
</inertia>
|
|
<mass>1.0</mass>
|
|
</inertial>
|
|
|
|
<collision name="base_collision">
|
|
<pose>-0.064 0 0.048 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.265 0.265 0.089</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
|
|
<visual name="base_visual">
|
|
<pose>-0.064 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://turtlebot3_waffle/meshes/waffle_base.dae</uri>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
</link>
|
|
|
|
<link name="imu_link">
|
|
<sensor name="tb3_imu" type="imu">
|
|
<always_on>true</always_on>
|
|
<update_rate>200</update_rate>
|
|
<imu>
|
|
<angular_velocity>
|
|
<x>
|
|
<noise type="gaussian">
|
|
<mean>0.0</mean>
|
|
<stddev>2e-4</stddev>
|
|
</noise>
|
|
</x>
|
|
<y>
|
|
<noise type="gaussian">
|
|
<mean>0.0</mean>
|
|
<stddev>2e-4</stddev>
|
|
</noise>
|
|
</y>
|
|
<z>
|
|
<noise type="gaussian">
|
|
<mean>0.0</mean>
|
|
<stddev>2e-4</stddev>
|
|
</noise>
|
|
</z>
|
|
</angular_velocity>
|
|
<linear_acceleration>
|
|
<x>
|
|
<noise type="gaussian">
|
|
<mean>0.0</mean>
|
|
<stddev>1.7e-2</stddev>
|
|
</noise>
|
|
</x>
|
|
<y>
|
|
<noise type="gaussian">
|
|
<mean>0.0</mean>
|
|
<stddev>1.7e-2</stddev>
|
|
</noise>
|
|
</y>
|
|
<z>
|
|
<noise type="gaussian">
|
|
<mean>0.0</mean>
|
|
<stddev>1.7e-2</stddev>
|
|
</noise>
|
|
</z>
|
|
</linear_acceleration>
|
|
</imu>
|
|
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
|
|
<ros>
|
|
<!-- <namespace>/tb3</namespace> -->
|
|
<remapping>~/out:=imu</remapping>
|
|
</ros>
|
|
</plugin>
|
|
</sensor>
|
|
</link>
|
|
|
|
<link name="base_scan">
|
|
<inertial>
|
|
<pose>-0.052 0 0.111 0 0 0</pose>
|
|
<inertia>
|
|
<ixx>0.001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.001</izz>
|
|
</inertia>
|
|
<mass>0.125</mass>
|
|
</inertial>
|
|
|
|
<collision name="lidar_sensor_collision">
|
|
<pose>-0.052 0 0.111 0 0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.0508</radius>
|
|
<length>0.055</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
|
|
<visual name="lidar_sensor_visual">
|
|
<pose>-0.064 0 0.121 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://turtlebot3_waffle/meshes/lds.dae</uri>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
|
|
<sensor name="hls_lfcd_lds" type="ray">
|
|
<always_on>true</always_on>
|
|
<visualize>true</visualize>
|
|
<pose>-0.064 0 0.121 0 0 0</pose>
|
|
<update_rate>5</update_rate>
|
|
<ray>
|
|
<scan>
|
|
<horizontal>
|
|
<samples>360</samples>
|
|
<resolution>1.000000</resolution>
|
|
<min_angle>0.000000</min_angle>
|
|
<max_angle>6.280000</max_angle>
|
|
</horizontal>
|
|
</scan>
|
|
<range>
|
|
<min>0.120000</min>
|
|
<max>3.5</max>
|
|
<resolution>0.015000</resolution>
|
|
</range>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.01</stddev>
|
|
</noise>
|
|
</ray>
|
|
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
|
|
<ros>
|
|
<!-- <namespace>/tb3</namespace> -->
|
|
<remapping>~/out:=scan</remapping>
|
|
</ros>
|
|
<output_type>sensor_msgs/LaserScan</output_type>
|
|
<frame_name>base_scan</frame_name>
|
|
</plugin>
|
|
</sensor>
|
|
</link>
|
|
|
|
<link name="wheel_left_link">
|
|
|
|
<inertial>
|
|
<pose>0.0 0.144 0.023 -1.57 0 0</pose>
|
|
<inertia>
|
|
<ixx>0.001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.001</izz>
|
|
</inertia>
|
|
<mass>0.1</mass>
|
|
</inertial>
|
|
|
|
<collision name="wheel_left_collision">
|
|
<pose>0.0 0.144 0.023 -1.57 0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.033</radius>
|
|
<length>0.018</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<!-- This friction pamareter don't contain reliable data!! -->
|
|
<friction>
|
|
<ode>
|
|
<mu>100000.0</mu>
|
|
<mu2>100000.0</mu2>
|
|
<fdir1>0 0 0</fdir1>
|
|
<slip1>0.0</slip1>
|
|
<slip2>0.0</slip2>
|
|
</ode>
|
|
</friction>
|
|
<contact>
|
|
<ode>
|
|
<soft_cfm>0</soft_cfm>
|
|
<soft_erp>0.2</soft_erp>
|
|
<kp>1e+5</kp>
|
|
<kd>1</kd>
|
|
<max_vel>0.01</max_vel>
|
|
<min_depth>0.001</min_depth>
|
|
</ode>
|
|
</contact>
|
|
</surface>
|
|
</collision>
|
|
|
|
<visual name="wheel_left_visual">
|
|
<pose>0.0 0.144 0.023 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://turtlebot3_waffle/meshes/tire.dae</uri>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
</link>
|
|
|
|
<link name="wheel_right_link">
|
|
|
|
<inertial>
|
|
<pose>0.0 -0.144 0.023 -1.57 0 0</pose>
|
|
<inertia>
|
|
<ixx>0.001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.001</izz>
|
|
</inertia>
|
|
<mass>0.1</mass>
|
|
</inertial>
|
|
|
|
<collision name="wheel_right_collision">
|
|
<pose>0.0 -0.144 0.023 -1.57 0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.033</radius>
|
|
<length>0.018</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<surface>
|
|
<!-- This friction pamareter don't contain reliable data!! -->
|
|
<friction>
|
|
<ode>
|
|
<mu>100000.0</mu>
|
|
<mu2>100000.0</mu2>
|
|
<fdir1>0 0 0</fdir1>
|
|
<slip1>0.0</slip1>
|
|
<slip2>0.0</slip2>
|
|
</ode>
|
|
</friction>
|
|
<contact>
|
|
<ode>
|
|
<soft_cfm>0</soft_cfm>
|
|
<soft_erp>0.2</soft_erp>
|
|
<kp>1e+5</kp>
|
|
<kd>1</kd>
|
|
<max_vel>0.01</max_vel>
|
|
<min_depth>0.001</min_depth>
|
|
</ode>
|
|
</contact>
|
|
</surface>
|
|
</collision>
|
|
|
|
<visual name="wheel_right_visual">
|
|
<pose>0.0 -0.144 0.023 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://turtlebot3_waffle/meshes/tire.dae</uri>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
</link>
|
|
|
|
<link name='caster_back_right_link'>
|
|
<pose>-0.177 -0.064 -0.004 0 0 0</pose>
|
|
<inertial>
|
|
<mass>0.001</mass>
|
|
<inertia>
|
|
<ixx>0.00001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.00001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.00001</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='collision'>
|
|
<geometry>
|
|
<sphere>
|
|
<radius>0.005000</radius>
|
|
</sphere>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<soft_cfm>0</soft_cfm>
|
|
<soft_erp>0.2</soft_erp>
|
|
<kp>1e+5</kp>
|
|
<kd>1</kd>
|
|
<max_vel>0.01</max_vel>
|
|
<min_depth>0.001</min_depth>
|
|
</ode>
|
|
</contact>
|
|
</surface>
|
|
</collision>
|
|
</link>
|
|
|
|
<link name='caster_back_left_link'>
|
|
<pose>-0.177 0.064 -0.004 0 0 0</pose>
|
|
<inertial>
|
|
<mass>0.001</mass>
|
|
<inertia>
|
|
<ixx>0.00001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.00001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.00001</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<collision name='collision'>
|
|
<geometry>
|
|
<sphere>
|
|
<radius>0.005000</radius>
|
|
</sphere>
|
|
</geometry>
|
|
<surface>
|
|
<contact>
|
|
<ode>
|
|
<soft_cfm>0</soft_cfm>
|
|
<soft_erp>0.2</soft_erp>
|
|
<kp>1e+5</kp>
|
|
<kd>1</kd>
|
|
<max_vel>0.01</max_vel>
|
|
<min_depth>0.001</min_depth>
|
|
</ode>
|
|
</contact>
|
|
</surface>
|
|
</collision>
|
|
</link>
|
|
|
|
<link name="camera_link"/>
|
|
|
|
<link name="camera_rgb_frame">
|
|
<inertial>
|
|
<pose>0.069 -0.047 0.107 0 0 0</pose>
|
|
<inertia>
|
|
<ixx>0.001</ixx>
|
|
<ixy>0.000</ixy>
|
|
<ixz>0.000</ixz>
|
|
<iyy>0.001</iyy>
|
|
<iyz>0.000</iyz>
|
|
<izz>0.001</izz>
|
|
</inertia>
|
|
<mass>0.035</mass>
|
|
</inertial>
|
|
|
|
<collision name="collision">
|
|
<pose>0 0.047 0 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.008 0.130 0.022</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
<pose>0.069 -0.047 0.107 0 0 0</pose>
|
|
<sensor name="camera" type="camera">
|
|
<always_on>true</always_on>
|
|
<visualize>true</visualize>
|
|
<update_rate>30</update_rate>
|
|
<camera name="intel_realsense_r200">
|
|
<horizontal_fov>1.02974</horizontal_fov>
|
|
<image>
|
|
<width>1920</width>
|
|
<height>1080</height>
|
|
<format>R8G8B8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.02</near>
|
|
<far>300</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<!-- Noise is sampled independently per pixel on each frame.
|
|
That pixel's noise value is added to each of its color
|
|
channels, which at that point lie in the range [0,1]. -->
|
|
<mean>0.0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
<plugin name="camera_driver" filename="libgazebo_ros_camera.so">
|
|
<ros>
|
|
<!-- <namespace>test_cam</namespace> -->
|
|
<!-- <remapping>image_raw:=image_demo</remapping> -->
|
|
<!-- <remapping>camera_info:=camera_info_demo</remapping> -->
|
|
</ros>
|
|
<!-- camera_name>omit so it defaults to sensor name</camera_name-->
|
|
<!-- frame_name>omit so it defaults to link name</frameName-->
|
|
<!-- <hack_baseline>0.07</hack_baseline> -->
|
|
</plugin>
|
|
</sensor>
|
|
</link>
|
|
|
|
<joint name="base_joint" type="fixed">
|
|
<parent>base_footprint</parent>
|
|
<child>base_link</child>
|
|
<pose>0.0 0.0 0.010 0 0 0</pose>
|
|
</joint>
|
|
|
|
<joint name="wheel_left_joint" type="revolute">
|
|
<parent>base_link</parent>
|
|
<child>wheel_left_link</child>
|
|
<pose>0.0 0.144 0.023 -1.57 0 0</pose>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<joint name="wheel_right_joint" type="revolute">
|
|
<parent>base_link</parent>
|
|
<child>wheel_right_link</child>
|
|
<pose>0.0 -0.144 0.023 -1.57 0 0</pose>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<joint name='caster_back_right_joint' type='ball'>
|
|
<parent>base_link</parent>
|
|
<child>caster_back_right_link</child>
|
|
</joint>
|
|
|
|
<joint name='caster_back_left_joint' type='ball'>
|
|
<parent>base_link</parent>
|
|
<child>caster_back_left_link</child>
|
|
</joint>
|
|
|
|
<joint name="imu_joint" type="fixed">
|
|
<parent>base_link</parent>
|
|
<child>imu_link</child>
|
|
<pose>-0.032 0 0.068 0 0 0</pose>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<joint name="lidar_joint" type="fixed">
|
|
<parent>base_link</parent>
|
|
<child>base_scan</child>
|
|
<pose>-0.064 0 0.121 0 0 0</pose>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<joint name="camera_joint" type="fixed">
|
|
<parent>base_link</parent>
|
|
<child>camera_link</child>
|
|
<pose>0.064 -0.065 0.094 0 0 0</pose>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<joint name="camera_rgb_joint" type="fixed">
|
|
<parent>camera_link</parent>
|
|
<child>camera_rgb_frame</child>
|
|
<pose>0.005 0.018 0.013 0 0 0</pose>
|
|
<axis>
|
|
<xyz>0 0 1</xyz>
|
|
</axis>
|
|
</joint>
|
|
|
|
<plugin name="turtlebot3_diff_drive" filename="libgazebo_ros_diff_drive.so">
|
|
|
|
<ros>
|
|
<!-- <namespace>/tb3</namespace> -->
|
|
</ros>
|
|
|
|
<update_rate>30</update_rate>
|
|
|
|
<!-- wheels -->
|
|
<left_joint>wheel_left_joint</left_joint>
|
|
<right_joint>wheel_right_joint</right_joint>
|
|
|
|
<!-- kinematics -->
|
|
<wheel_separation>0.287</wheel_separation>
|
|
<wheel_diameter>0.066</wheel_diameter>
|
|
|
|
<!-- limits -->
|
|
<max_wheel_torque>20</max_wheel_torque>
|
|
<max_wheel_acceleration>1.0</max_wheel_acceleration>
|
|
|
|
<command_topic>cmd_vel</command_topic>
|
|
|
|
<!-- output -->
|
|
<publish_odom>true</publish_odom>
|
|
<publish_odom_tf>true</publish_odom_tf>
|
|
<publish_wheel_tf>false</publish_wheel_tf>
|
|
|
|
<odometry_topic>odom</odometry_topic>
|
|
<odometry_frame>odom</odometry_frame>
|
|
<robot_base_frame>base_footprint</robot_base_frame>
|
|
|
|
</plugin>
|
|
|
|
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
|
|
<ros>
|
|
<!-- <namespace>/tb3</namespace> -->
|
|
<remapping>~/out:=joint_states</remapping>
|
|
</ros>
|
|
<update_rate>30</update_rate>
|
|
<joint_name>wheel_left_joint</joint_name>
|
|
<joint_name>wheel_right_joint</joint_name>
|
|
</plugin>
|
|
|
|
</model>
|
|
</sdf>
|