|
@@ -0,0 +1,535 @@
|
|
|
|
|
+<?xml version="1.0" encoding="utf-8"?>
|
|
|
|
|
+<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
|
|
|
|
|
+ Commit Version: 1.6.0-1-g15f4949 Build Version: 1.6.7594.29634
|
|
|
|
|
+ For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
|
|
|
|
|
+<robot
|
|
|
|
|
+ name="hunter2_base">
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="chass">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0.0266989327622036 0.000409203500587652 -0.135901124750884"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="21.02945169536679" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.0332370959804736"
|
|
|
|
|
+ ixy="-1.013150489971E-06"
|
|
|
|
|
+ ixz="-0.00188859201421112"
|
|
|
|
|
+ iyy="0.111072002332437"
|
|
|
|
|
+ iyz="-5.13308150598312E-07"
|
|
|
|
|
+ izz="0.12660862809283" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/chass.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/chass.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="front_steer_left_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-0.012614 1.8116E-05 0.0023132"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="7.8526" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.063827"
|
|
|
|
|
+ ixy="0"
|
|
|
|
|
+ ixz="0"
|
|
|
|
|
+ iyy="0.063827"
|
|
|
|
|
+ iyz="0"
|
|
|
|
|
+ izz="0.11091" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="front_steer_left_joint"
|
|
|
|
|
+ type="revolute">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0.37142 0.29199 -0.1955"
|
|
|
|
|
+ rpy="1.5708 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="chass" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="front_steer_left_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 1 0" />
|
|
|
|
|
+ <limit
|
|
|
|
|
+ lower="-0.69"
|
|
|
|
|
+ upper="0.69"
|
|
|
|
|
+ effort="0"
|
|
|
|
|
+ velocity="0" />
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="front_left_wheel_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-6.5774E-06 2.0242E-05 -0.0096386"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="7.7007" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.063724"
|
|
|
|
|
+ ixy="0"
|
|
|
|
|
+ ixz="0"
|
|
|
|
|
+ iyy="0.063724"
|
|
|
|
|
+ iyz="0"
|
|
|
|
|
+ izz="0.11072" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/front_left_wheel_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/front_left_wheel_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="front_left_wheel_joint"
|
|
|
|
|
+ type="continuous">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="front_steer_left_link" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="front_left_wheel_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 0 -1" />
|
|
|
|
|
+ <dynamics damping="0.0" friction="15"/>
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="front_steer_right_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-8.9374E-08 1.0997E-07 0.0095958"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="7.696" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.063704"
|
|
|
|
|
+ ixy="0"
|
|
|
|
|
+ ixz="0"
|
|
|
|
|
+ iyy="0.063704"
|
|
|
|
|
+ iyz="0"
|
|
|
|
|
+ izz="0.11068" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="front_steer_right_joint"
|
|
|
|
|
+ type="revolute">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0.37142 -0.29201 -0.1955"
|
|
|
|
|
+ rpy="1.5708 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="chass" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="front_steer_right_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 1 0" />
|
|
|
|
|
+ <limit
|
|
|
|
|
+ lower="-0.69"
|
|
|
|
|
+ upper="0.69"
|
|
|
|
|
+ effort="0"
|
|
|
|
|
+ velocity="0" />
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="front_right_wheel_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-9.1148E-08 1.1284E-07 0.0095049"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="7.5613" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.063626"
|
|
|
|
|
+ ixy="0"
|
|
|
|
|
+ ixz="0"
|
|
|
|
|
+ iyy="0.063626"
|
|
|
|
|
+ iyz="0"
|
|
|
|
|
+ izz="0.11054" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 3.14 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/front_left_wheel_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/front_right_wheel_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="front_right_wheel_joint"
|
|
|
|
|
+ type="continuous">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="front_steer_right_link" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="front_right_wheel_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 0 -1" />
|
|
|
|
|
+ <dynamics damping="0.0" friction="15"/>
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="left_rear_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-8.826E-05 6.4342E-05 -0.0096491"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="7.6692" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.063699"
|
|
|
|
|
+ ixy="0"
|
|
|
|
|
+ ixz="0"
|
|
|
|
|
+ iyy="0.063699"
|
|
|
|
|
+ iyz="0"
|
|
|
|
|
+ izz="0.11067" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/left_rear_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/left_rear_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="left_rear_joint"
|
|
|
|
|
+ type="continuous">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-0.28 0.29249 -0.19558"
|
|
|
|
|
+ rpy="1.5708 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="chass" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="left_rear_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 0 -1" />
|
|
|
|
|
+ <dynamics damping="0.0" friction="15"/>
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="right_rear_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="8.6344E-05 7.4488E-05 0.0097824"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="7.7133" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="0.06373"
|
|
|
|
|
+ ixy="0"
|
|
|
|
|
+ ixz="0"
|
|
|
|
|
+ iyy="0.06373"
|
|
|
|
|
+ iyz="0"
|
|
|
|
|
+ izz="0.11073" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/right_rear_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <mesh
|
|
|
|
|
+ filename="package://hunter2_base/meshes/right_rear_link.STL" />
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="right_rear_joint"
|
|
|
|
|
+ type="continuous">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-0.28018 -0.29251 -0.19558"
|
|
|
|
|
+ rpy="1.5708 0.0026575 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="chass" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="right_rear_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 0 -1" />
|
|
|
|
|
+ <dynamics damping="0.0" friction="15"/>
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="front_steer_link">
|
|
|
|
|
+ <inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0.049836 8.1046E-15 0.017912"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="0.0049179" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="1.6846E-07"
|
|
|
|
|
+ ixy="7.6396E-23"
|
|
|
|
|
+ ixz="-1.0974E-08"
|
|
|
|
|
+ iyy="7.549E-07"
|
|
|
|
|
+ iyz="-1.8957E-22"
|
|
|
|
|
+ izz="7.334E-07" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="0.79216 0.81961 0.93333 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="front_steer_joint"
|
|
|
|
|
+ type="revolute">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0.44792 -1.1431E-05 -0.121"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="chass" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="front_steer_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 0 1" />
|
|
|
|
|
+ <limit
|
|
|
|
|
+ lower="-0.72"
|
|
|
|
|
+ upper="0.72"
|
|
|
|
|
+ effort="0"
|
|
|
|
|
+ velocity="0" />
|
|
|
|
|
+ </joint>
|
|
|
|
|
+ <link
|
|
|
|
|
+ name="rear_wheel_link">
|
|
|
|
|
+<inertial>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-0.02 0.0031269 -0.12735"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <mass
|
|
|
|
|
+ value="0.0049179" />
|
|
|
|
|
+ <inertia
|
|
|
|
|
+ ixx="1.1821E-06"
|
|
|
|
|
+ ixy="9.6965E-13"
|
|
|
|
|
+ ixz="-3.1553E-12"
|
|
|
|
|
+ iyy="9.5276E-07"
|
|
|
|
|
+ iyz="1.2428E-08"
|
|
|
|
|
+ izz="1.0913E-06" />
|
|
|
|
|
+ </inertial>
|
|
|
|
|
+ <visual>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ <material
|
|
|
|
|
+ name="">
|
|
|
|
|
+ <color
|
|
|
|
|
+ rgba="1 1 1 1" />
|
|
|
|
|
+ </material>
|
|
|
|
|
+ </visual>
|
|
|
|
|
+ <collision>
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="0 0 0"
|
|
|
|
|
+ rpy="0 0 0" />
|
|
|
|
|
+ <geometry>
|
|
|
|
|
+ <cylinder length="0.001" radius="0.005"/>
|
|
|
|
|
+ </geometry>
|
|
|
|
|
+ </collision>
|
|
|
|
|
+ </link>
|
|
|
|
|
+ <joint
|
|
|
|
|
+ name="rear_wheel_joint"
|
|
|
|
|
+ type="continuous">
|
|
|
|
|
+ <origin
|
|
|
|
|
+ xyz="-0.42408 -1.1431E-05 -0.085581"
|
|
|
|
|
+ rpy="0.0032313 0 0" />
|
|
|
|
|
+ <parent
|
|
|
|
|
+ link="chass" />
|
|
|
|
|
+ <child
|
|
|
|
|
+ link="rear_wheel_link" />
|
|
|
|
|
+ <axis
|
|
|
|
|
+ xyz="0 0 1" />
|
|
|
|
|
+ <dynamics damping="0.0" friction="15"/>
|
|
|
|
|
+ </joint>
|
|
|
|
|
+
|
|
|
|
|
+ <gazebo reference="front_left_wheel_link">
|
|
|
|
|
+ <mu1>0.8</mu1>
|
|
|
|
|
+ <mu2>0.8</mu2>
|
|
|
|
|
+ <kp>10000000.0</kp>
|
|
|
|
|
+ <kd>1.0</kd>
|
|
|
|
|
+ <minDepth>0.001</minDepth>
|
|
|
|
|
+ <maxVel>0.1</maxVel>
|
|
|
|
|
+ <fdir1>1 0 0</fdir1>
|
|
|
|
|
+ <material>Gazebo/Grey </material>
|
|
|
|
|
+ </gazebo>
|
|
|
|
|
+ <gazebo reference="front_right_wheel_link">
|
|
|
|
|
+ <mu1>0.8</mu1>
|
|
|
|
|
+ <mu2>0.8</mu2>
|
|
|
|
|
+ <kp>10000000.0</kp>
|
|
|
|
|
+ <kd>1.0</kd>
|
|
|
|
|
+ <minDepth>0.001</minDepth>
|
|
|
|
|
+ <maxVel>0.1</maxVel>
|
|
|
|
|
+ <fdir1>1 0 0</fdir1>
|
|
|
|
|
+ <material>Gazebo/Grey </material>
|
|
|
|
|
+ </gazebo>
|
|
|
|
|
+ <gazebo reference="right_rear_link">
|
|
|
|
|
+ <mu1>0.8</mu1>
|
|
|
|
|
+ <mu2>10</mu2>
|
|
|
|
|
+ <kp>10000000.0</kp>
|
|
|
|
|
+ <kd>1.0</kd>
|
|
|
|
|
+ <minDepth>0.001</minDepth>
|
|
|
|
|
+ <maxVel>0.1</maxVel>
|
|
|
|
|
+ <fdir1>1 0 0</fdir1>
|
|
|
|
|
+ <material>Gazebo/Grey </material>
|
|
|
|
|
+ </gazebo>
|
|
|
|
|
+ <gazebo reference="left_rear_link">
|
|
|
|
|
+ <mu1>0.8</mu1>
|
|
|
|
|
+ <mu2>10</mu2>
|
|
|
|
|
+ <kp>10000000.0</kp>
|
|
|
|
|
+ <kd>1.0</kd>
|
|
|
|
|
+ <minDepth>0.001</minDepth>
|
|
|
|
|
+ <maxVel>0.1</maxVel>
|
|
|
|
|
+ <fdir1>1 0 0</fdir1>
|
|
|
|
|
+ <material>Gazebo/Grey </material>
|
|
|
|
|
+ </gazebo>
|
|
|
|
|
+
|
|
|
|
|
+ <gazebo>
|
|
|
|
|
+ <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
|
|
|
|
+ <robotSimType>steer_bot_hardware_gazebo/SteerBotHardwareGazebo</robotSimType>
|
|
|
|
|
+ <legacyModeNS>false</legacyModeNS>
|
|
|
|
|
+ </plugin>
|
|
|
|
|
+ </gazebo>
|
|
|
|
|
+
|
|
|
|
|
+
|
|
|
|
|
+
|
|
|
|
|
+
|
|
|
|
|
+</robot>
|