370 lines
9.6 KiB
Plaintext
370 lines
9.6 KiB
Plaintext
![]() |
<?xml version="1.0" ?>
|
||
|
<sdf version="1.5">
|
||
|
<model name="husky">
|
||
|
<pose>0 0 .5 0 0 0</pose>
|
||
|
<!-- Main Chassis -->
|
||
|
<link name="base_link">
|
||
|
<!-- Physics -->
|
||
|
<collision name="collision">
|
||
|
<!-- <pose>0 0 -0.3 0 0 0</pose> -->
|
||
|
<pose>0 0 0.1 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<box>
|
||
|
<size>1.0074 0.5709 0.2675</size>
|
||
|
</box>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<inertial>
|
||
|
<mass>33.855</mass>
|
||
|
<pose>-0.0856132 -0.000839955 0.238145 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>2.2343</ixx>
|
||
|
<ixy>-0.023642</ixy>
|
||
|
<ixz>0.275174</ixz>
|
||
|
<iyy>3.42518</iyy>
|
||
|
<iyz>0.00239624</iyz>
|
||
|
<izz>2.1241</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<!-- Visual -->
|
||
|
<!-- Base frame -->
|
||
|
<visual name="base">
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/base_link.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/FlatBlack</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<!-- Top Plate -->
|
||
|
<visual name="top_plate">
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/top_plate.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Yellow</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<!-- Front Bumper -->
|
||
|
<visual name="front_bumper">
|
||
|
<pose>0.47 0 0.091 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/bumper.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/FlatBlack</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<!-- Rear Bumper -->
|
||
|
<visual name="rear_bumper">
|
||
|
<pose>-0.47 0 0.091 0 0 3.141</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/bumper.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/FlatBlack</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<!-- User Rail -->
|
||
|
<visual name="user_rail">
|
||
|
<pose>0.272 0 0.245 0 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/user_rail.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Grey</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<!-- Back Left Wheel -->
|
||
|
<link name="back_left_wheel">
|
||
|
<pose>-0.256 0.285475 0.035 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<mass>2.6357</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0246688</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0246688</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0441058</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="back_left_wheel_collision">
|
||
|
<pose>0 0 0 -1.5707 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.17775</radius>
|
||
|
<length>0.1143</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>100000.0</mu>
|
||
|
<mu2>100000.0</mu2>
|
||
|
<slip1>0.0</slip1>
|
||
|
<slip2>0.0</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="back_left_wheel">
|
||
|
<pose>0 0 0 -3.14159 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/wheel.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Grey</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name="back_left_joint" type="revolute">
|
||
|
<parent>base_link</parent>
|
||
|
<child>back_left_wheel</child>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<!-- Back Right Wheel -->
|
||
|
<link name="back_right_wheel">
|
||
|
<pose>-0.256 -0.285475 0.035 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<mass>2.6357</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0246688</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0246688</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0441058</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="back_right_wheel_collision">
|
||
|
<pose>0 0 0 -1.5707 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.17775</radius>
|
||
|
<length>0.1143</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>100000.0</mu>
|
||
|
<mu2>100000.0</mu2>
|
||
|
<slip1>0.0</slip1>
|
||
|
<slip2>0.0</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="back_right_wheel">
|
||
|
<pose>0 0 0 -3.14159 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/wheel.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Grey</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name="back_right_joint" type="revolute">
|
||
|
<parent>base_link</parent>
|
||
|
<child>back_right_wheel</child>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<!-- Front Left Wheel -->
|
||
|
<link name="front_left_wheel">
|
||
|
<pose>0.256 0.285475 0.035 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<mass>2.6357</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0246688</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0246688</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0441058</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="front_left_wheel_collision">
|
||
|
<pose>0 0 0 -1.5707 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.17775</radius>
|
||
|
<length>0.1143</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>100000.0</mu>
|
||
|
<mu2>100000.0</mu2>
|
||
|
<slip1>0.0</slip1>
|
||
|
<slip2>0.0</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="front_left_wheel">
|
||
|
<pose>0 0 0 -3.14159 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/wheel.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Grey</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name="front_left_joint" type="revolute">
|
||
|
<parent>base_link</parent>
|
||
|
<child>front_left_wheel</child>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<!-- Front Right Wheel -->
|
||
|
<link name="front_right_wheel">
|
||
|
<pose>0.256 -0.285475 0.035 0 0 0</pose>
|
||
|
<inertial>
|
||
|
<mass>2.6357</mass>
|
||
|
<pose>0 0 0 0 0 0</pose>
|
||
|
<inertia>
|
||
|
<ixx>0.0246688</ixx>
|
||
|
<ixy>0</ixy>
|
||
|
<ixz>0</ixz>
|
||
|
<iyy>0.0246688</iyy>
|
||
|
<iyz>0</iyz>
|
||
|
<izz>0.0441058</izz>
|
||
|
</inertia>
|
||
|
</inertial>
|
||
|
<collision name="front_right_wheel_collision">
|
||
|
<pose>0 0 0 -1.5707 0 0</pose>
|
||
|
<geometry>
|
||
|
<cylinder>
|
||
|
<radius>0.17775</radius>
|
||
|
<length>0.1143</length>
|
||
|
</cylinder>
|
||
|
</geometry>
|
||
|
<surface>
|
||
|
<friction>
|
||
|
<ode>
|
||
|
<mu>100000.0</mu>
|
||
|
<mu2>100000.0</mu2>
|
||
|
<slip1>0.0</slip1>
|
||
|
<slip2>0.0</slip2>
|
||
|
</ode>
|
||
|
</friction>
|
||
|
</surface>
|
||
|
</collision>
|
||
|
<visual name="front_right_wheel">
|
||
|
<pose>0 0 0 -3.14159 0 0</pose>
|
||
|
<geometry>
|
||
|
<mesh>
|
||
|
<uri>model://husky/meshes/wheel.stl</uri>
|
||
|
</mesh>
|
||
|
</geometry>
|
||
|
<material>
|
||
|
<script>
|
||
|
<name>Gazebo/Grey</name>
|
||
|
</script>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name="front_right_joint" type="revolute">
|
||
|
<parent>base_link</parent>
|
||
|
<child>front_right_wheel</child>
|
||
|
<axis>
|
||
|
<xyz>0 1 0</xyz>
|
||
|
<use_parent_model_frame>true</use_parent_model_frame>
|
||
|
</axis>
|
||
|
<physics>
|
||
|
<ode>
|
||
|
<limit>
|
||
|
<cfm>0.000000</cfm>
|
||
|
<erp>0.900000</erp>
|
||
|
</limit>
|
||
|
</ode>
|
||
|
</physics>
|
||
|
</joint>
|
||
|
<plugin name="husky_diff_controller" filename="libhusky_gazebo_plugins.so">
|
||
|
<alwaysOn>true</alwaysOn>
|
||
|
<updateRate>100.0</updateRate>
|
||
|
<backLeftJoint>back_left_joint</backLeftJoint>
|
||
|
<backRightJoint>back_right_joint</backRightJoint>
|
||
|
<frontLeftJoint>front_left_joint</frontLeftJoint>
|
||
|
<frontRightJoint>front_right_joint</frontRightJoint>
|
||
|
<wheelSeparation>0.5709</wheelSeparation>
|
||
|
<wheelDiameter>0.3555</wheelDiameter>
|
||
|
<torque>35</torque>
|
||
|
</plugin>
|
||
|
</model>
|
||
|
</sdf>
|