2021-01-20 17:32:37 +05:30

261 lines
6.3 KiB
XML

<?xml version='1.0'?>
<sdf version='1.5'>
<model name="qt_pi_rgb">
<link name='chassis'>
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass>20</mass>
<pose>0.10 0 -0.05 0 0 0</pose>
</inertial>
<collision name='collision'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</visual>
<collision name='caster_collision'>
<pose>0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='caster_visual'>
<pose>0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
</visual>
</link>
<link name="left_wheel">
<pose>-0.1 0.2 0.1 0 0 0</pose>
<inertial>
<mass>5</mass>
</inertial>
<collision name="collision">
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
<geometry>
<sphere>
<radius>.1</radius>
</sphere>
</geometry>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>.1</radius>
</sphere>
</geometry>
</visual>
</link>
<link name="right_wheel">
<pose>-0.1 -0.2 0.1 0 0 0</pose>
<inertial>
<mass>5</mass>
</inertial>
<collision name="collision">
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0.0</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
<geometry>
<sphere>
<radius>.1</radius>
</sphere>
</geometry>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>.1</radius>
</sphere>
</geometry>
</visual>
</link>
<joint type="revolute" name="left_wheel_hinge">
<pose>0 0 0 0 0 0</pose>
<child>left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint type="revolute" name="right_wheel_hinge">
<pose>0 0 0 0 0 0</pose>
<child>right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<link name='cam_link'>
<pose>0.22 0 0.15 0 0.785 0</pose>
<inertial>
<mass>0.0001</mass>
</inertial>
<collision name='cam_collision'>
<geometry>
<box>
<size>.05 .05 .05</size>
</box>
</geometry>
</collision>
<visual name='cam_visual'>
<geometry>
<box>
<size>.05 .05 .05</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>648</width>
<height>488</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_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>front_camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</link>
<joint name="cam_joint" type="fixed">
<child>cam_link</child>
<parent>chassis</parent>
</joint>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<alwaysOn>true</alwaysOn>
<updateRate>30</updateRate>
<leftJoint>left_wheel_hinge</leftJoint>
<robotNamespace>qt_pi</robotNamespace>
<rightJoint>right_wheel_hinge</rightJoint>
<wheelSeparation>0.4</wheelSeparation>
<wheelDiameter>0.2</wheelDiameter>
<publishWheelTF>1</publishWheelTF>
<wheelTorque>5</wheelTorque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_link</robotBaseFrame>
<odometryFrame>odom</odometryFrame>
<publishTf>1</publishTf>
<publishOdomTF>true</publishOdomTF>
<rosDebugLevel>1</rosDebugLevel>
<publishWheelJointState>false</publishWheelJointState>
<wheelAcceleration>0</wheelAcceleration>
</plugin>
</model>
</sdf>