revert minitaur.urdf to previous (backward compatibility) and add _v1 for better version.
This commit is contained in:
@@ -267,11 +267,6 @@
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<cylinder length="0.026" radius="0.0434"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.25"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
@@ -432,10 +427,8 @@
|
||||
|
||||
<link name="lower_leg_front_rightR_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -455,12 +448,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_front_rightR_link" type="continuous">
|
||||
<joint name="knee_front_rightR_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_front_rightR_link"/>
|
||||
<child link="lower_leg_front_rightR_link"/>
|
||||
@@ -503,10 +495,8 @@
|
||||
|
||||
<link name="lower_leg_front_rightL_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -526,12 +516,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_front_rightL_link" type="continuous">
|
||||
<joint name="knee_front_rightL_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_front_rightL_link"/>
|
||||
<child link="lower_leg_front_rightL_link"/>
|
||||
@@ -572,10 +561,8 @@
|
||||
|
||||
<link name="lower_leg_front_leftR_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -595,12 +582,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0.0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_front_leftR_link" type="continuous">
|
||||
<joint name="knee_front_leftR_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_front_leftR_link"/>
|
||||
<child link="lower_leg_front_leftR_link"/>
|
||||
@@ -642,10 +628,8 @@
|
||||
|
||||
<link name="lower_leg_front_leftL_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -665,12 +649,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0.0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_front_leftL_link" type="continuous">
|
||||
<joint name="knee_front_leftL_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_front_leftL_link"/>
|
||||
<child link="lower_leg_front_leftL_link"/>
|
||||
@@ -709,10 +692,8 @@
|
||||
|
||||
<link name="lower_leg_back_rightR_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -732,12 +713,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_back_rightR_link" type="continuous">
|
||||
<joint name="knee_back_rightR_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_back_rightR_link"/>
|
||||
<child link="lower_leg_back_rightR_link"/>
|
||||
@@ -780,10 +760,8 @@
|
||||
|
||||
<link name="lower_leg_back_rightL_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -803,12 +781,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_back_rightL_link" type="continuous">
|
||||
<joint name="knee_back_rightL_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_back_rightL_link"/>
|
||||
<child link="lower_leg_back_rightL_link"/>
|
||||
@@ -849,10 +826,8 @@
|
||||
|
||||
<link name="lower_leg_back_leftR_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -872,12 +847,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_back_leftR_link" type="continuous">
|
||||
<joint name="knee_back_leftR_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_back_leftR_link"/>
|
||||
<child link="lower_leg_back_leftR_link"/>
|
||||
@@ -917,10 +891,8 @@
|
||||
|
||||
<link name="lower_leg_back_leftL_link">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value=".3"/>
|
||||
<stiffness value="10000"/>
|
||||
<damping value="10"/>
|
||||
<lateral_friction value="1"/>
|
||||
</contact>
|
||||
|
||||
@@ -940,12 +912,11 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 .1"/>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="knee_back_leftL_link" type="continuous">
|
||||
<joint name="knee_back_leftL_link" type="revolute">
|
||||
<axis xyz="0 1 0"/>
|
||||
<parent link="upper_leg_back_leftL_link"/>
|
||||
<child link="lower_leg_back_leftL_link"/>
|
||||
|
||||
Reference in New Issue
Block a user