mirror of
https://gitlab.com/yikestone/qt_pi.git
synced 2025-08-03 13:44:12 +05:30
207 lines
6.8 KiB
XML
207 lines
6.8 KiB
XML
<?xml version='1.0'?>
|
|
<sdf version='1.5'>
|
|
<model name="qt_pi_laser">
|
|
<link name='chassis'>
|
|
|
|
<pose>0 0 0.0525 0 0 0</pose>
|
|
|
|
<inertial>
|
|
<mass>10</mass>
|
|
<pose>0 -0.02 -0.03 0 0 0</pose>
|
|
</inertial>
|
|
|
|
<collision name='collision'>
|
|
<geometry>
|
|
<box>
|
|
<size>.165 .156 .075</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
|
|
<visual name='visual'>
|
|
<pose>0 0.015 0.053 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://qt_pi_chassis/meshes/chassis.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
|
|
<collision name='caster_collision'>
|
|
<pose>0 -0.065 -0.045 0 0 0</pose>
|
|
<geometry>
|
|
<sphere>
|
|
<radius>.0075</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 -0.065 -0.04 0 3.141592653589793 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://qt_pi_wheel/meshes/ball_castor.dae</uri>
|
|
<scale>0.5 0.5 0.5</scale>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
|
|
</link>
|
|
|
|
<link name="left_wheel">
|
|
<pose>0.106 0.03 0.0227 0 0 -1.5707963267948966</pose>
|
|
<inertial>
|
|
<mass>10</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>.0227</radius>
|
|
</sphere>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<pose>0 -0.008 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://qt_pi_wheel/meshes/wheel.dae</uri>
|
|
<scale>0.056 0.056 0.056</scale>
|
|
</mesh>
|
|
</geometry>
|
|
</visual>
|
|
</link>
|
|
|
|
<link name="right_wheel">
|
|
<pose>-0.106 0.03 0.0227 0 0 -1.5707963267948966</pose>
|
|
<inertial>
|
|
<mass>10</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>0.0227</radius>
|
|
</sphere>
|
|
</geometry>
|
|
</collision>
|
|
<visual name="visual">
|
|
<pose>0 0 0 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://qt_pi_wheel/meshes/wheel.dae</uri>
|
|
<scale>0.056 0.056 0.056</scale>
|
|
</mesh>
|
|
|
|
</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>
|
|
|
|
<include>
|
|
<uri>model://hokuyo</uri>
|
|
<pose>0 0 0.102 0 0 -1.5707963267948966</pose>
|
|
</include>
|
|
|
|
<joint name="hokuyo_joint" type="fixed">
|
|
<child>hokuyo::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>0</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> |