summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <erwin.coumans@gmail.com>2019-05-22 10:59:20 -0400
committerErwin Coumans <erwin.coumans@gmail.com>2019-05-22 10:59:20 -0400
commitd7e863e51a68d0fc5a21475afeaa3cae5a568525 (patch)
tree870e3678751be0b7aa198b86b2c7f40b6f5589bc
parentaf5bfb4089a401be5684b132d14235cedeeabc14 (diff)
downloadbullet3-d7e863e51a68d0fc5a21475afeaa3cae5a568525.tar.gz
update microtaur URDF and example, to be compatible with minitaur_rainbow_dash
-rw-r--r--examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf1360
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/microtaur.py92
2 files changed, 689 insertions, 763 deletions
diff --git a/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf b/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf
index 6dcdf6f42..3d2afd832 100644
--- a/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf
+++ b/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf
@@ -1,4 +1,4 @@
-<?xml version="0.0" ?>
+<?xml version="1.0"?>
<!-- ======================================================================= -->
<!--LICENSE: -->
<!--Copyright (c) 2019, Erwin Coumans -->
@@ -53,9 +53,9 @@
<box size="0.092 0.105 0.045"/>
</geometry>
</collision>
- </link>
-
- <link name="plate0">
+ </link>
+
+ <link name="plate0">
<contact>
<lateral_friction value="0.3"/>
</contact>
@@ -196,9 +196,7 @@
<joint_properties damping="0.0" friction="0.0"/>
</joint>
-
-
- <link name="chassis_right">
+ <link name="chassis_right">
<contact>
<lateral_friction value="0.3"/>
</contact>
@@ -232,8 +230,7 @@
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
-
-
+
<link name="chassis_front">
<contact>
<lateral_friction value="0.3"/>
@@ -658,8 +655,7 @@
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
-
- <link name="chassis_left">
+ <link name="chassis_left">
<contact>
<lateral_friction value="0.3"/>
</contact>
@@ -694,735 +690,667 @@
<joint_properties damping="0.0" friction="0.0"/>
</joint>
-
-
- <link name="motor_front_rightR_link">
-
- <visual>
+ <link name="motor_front_rightR_link">
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- <material name="grey1">
- <color rgba="0. 1. 0. 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_front_rightR_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_right"/>
- <child link="motor_front_rightR_link"/>
- <origin rpy="1.57075 0 0" xyz="0.1335 -0.035 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
+ </geometry> </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_front_rightR_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_right"/>
+ <child link="motor_front_rightR_link"/>
+ <origin rpy="1.57075 0 0" xyz="0.1335 -.0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="motor_front_rightL_link">
-<collision>
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_front_rightL_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_right"/>
- <child link="motor_front_rightL_link"/>
- <origin rpy="1.57075 0 3.141592" xyz="0.1335 0.03 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="motor_front_leftL_link">
- <collision>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_front_rightL_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_right"/>
+ <child link="motor_front_rightL_link"/>
+ <origin rpy="1.57075 0 3.141592" xyz="0.1335 .0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="motor_front_leftL_link">
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_front_leftL_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_left"/>
- <child link="motor_front_leftL_link"/>
- <origin rpy="1.57075 0 3.141592" xyz="0.1335 0.035 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_front_leftL_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_left"/>
+ <child link="motor_front_leftL_link"/>
+ <origin rpy="1.57075 0 3.141592" xyz="0.1335 .0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="motor_front_leftR_link">
- <collision>
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_front_leftR_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_left"/>
- <child link="motor_front_leftR_link"/>
- <origin rpy="1.57075 0 0" xyz="0.1335 -0.03 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="motor_back_rightR_link">
- <collision>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_front_leftR_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_left"/>
+ <child link="motor_front_leftR_link"/>
+ <origin rpy="1.57075 0 0" xyz="0.1335 -.0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="motor_back_rightR_link">
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_back_rightR_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_right"/>
- <child link="motor_back_rightR_link"/>
- <origin rpy="1.57075 0 0" xyz="-0.1335 -0.035 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_back_rightR_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_right"/>
+ <child link="motor_back_rightR_link"/>
+ <origin rpy="1.57075 0 0" xyz="-0.1335 -.0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="motor_back_rightL_link">
- <collision>
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_back_rightL_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_right"/>
- <child link="motor_back_rightL_link"/>
- <origin rpy="1.57075 0 3.141592" xyz="-0.1335 0.03 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="motor_back_leftL_link">
- <collision>
- <geometry>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_back_rightL_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_right"/>
+ <child link="motor_back_rightL_link"/>
+ <origin rpy="1.57075 0 3.141592" xyz="-0.1335 .0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="motor_back_leftL_link">
+ <collision>
+ <geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_back_leftL_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_left"/>
- <child link="motor_back_leftL_link"/>
- <origin rpy="1.57075 0 3.141592" xyz="-0.1335 0.035 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_back_leftL_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_left"/>
+ <child link="motor_back_leftL_link"/>
+ <origin rpy="1.57075 0 3.141592" xyz="-0.1335 .0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="motor_back_leftR_link">
- <collision>
+ <collision>
<geometry>
<cylinder length="0.003" radius="0.0134"/>
- </geometry>
- </collision>
- <inertial>
- <mass value="0.01"/>
- <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
- </inertial>
- </link>
- <joint name="motor_back_leftR_joint" type="continuous">
- <axis xyz="0 0 1"/>
- <parent link="chassis_left"/>
- <child link="motor_back_leftR_link"/>
- <origin rpy="1.57075 0 0" xyz="-0.1335 -0.03 -0.08"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".002"/>
+ <inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
+ </inertial>
+ </link>
+ <joint name="motor_back_leftR_joint" type="continuous">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_left"/>
+ <child link="motor_back_leftR_link"/>
+ <origin rpy="1.57075 0 0" xyz="-0.1335 -.0275 -0.08"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="upper_leg_front_rightR_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="hip_front_rightR_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_front_rightR_link"/>
- <child link="upper_leg_front_rightR_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_front_rightR_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_front_rightR_link"/>
+ <child link="upper_leg_front_rightR_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="lower_leg_front_rightR_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_front_rightR_link"/>
- <child link="lower_leg_front_rightR_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="upper_leg_front_rightL_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="motor_front_rightL_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_front_rightL_link"/>
- <child link="upper_leg_front_rightL_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
-
-
- <link name="lower_leg_front_rightL_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .198"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .198"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_front_rightL_link"/>
- <child link="lower_leg_front_rightL_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <mass value=".086"/>
+ <inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
+ </inertial>
+ </link>
+ <joint name="knee_front_rightR_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_front_rightR_link"/>
+ <child link="lower_leg_front_rightR_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="upper_leg_front_rightL_link">
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_front_rightL_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_front_rightL_link"/>
+ <child link="upper_leg_front_rightL_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="lower_leg_front_rightL_link">
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .1"/>
+ <mass value=".072"/>
+ <inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
+ </inertial>
+ </link>
+ <joint name="knee_front_rightL_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_front_rightL_link"/>
+ <child link="lower_leg_front_rightL_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="upper_leg_front_leftR_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="hip_front_leftR_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_front_leftR_link"/>
- <child link="upper_leg_front_leftR_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_front_leftR_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_front_leftR_link"/>
+ <child link="upper_leg_front_leftR_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="lower_leg_front_leftR_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0.0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0.0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_front_leftR_link"/>
- <child link="lower_leg_front_leftR_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
-
- <link name="upper_leg_front_leftL_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="motor_front_leftL_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_front_leftL_link"/>
- <child link="upper_leg_front_leftL_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="lower_leg_front_leftL_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0.0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .198"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0.0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .198"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_front_leftL_link"/>
- <child link="lower_leg_front_leftL_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .1"/>
+ <mass value=".072"/>
+ <inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
+ </inertial>
+ </link>
+ <joint name="knee_front_leftR_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_front_leftR_link"/>
+ <child link="lower_leg_front_leftR_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="upper_leg_front_leftL_link">
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_front_leftL_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_front_leftL_link"/>
+ <child link="upper_leg_front_leftL_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="lower_leg_front_leftL_link">
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <mass value=".086"/>
+ <inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
+ </inertial>
+ </link>
+ <joint name="knee_front_leftL_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_front_leftL_link"/>
+ <child link="lower_leg_front_leftL_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="upper_leg_back_rightR_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="hip_rightR_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_back_rightR_link"/>
- <child link="upper_leg_back_rightR_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_back_rightR_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_back_rightR_link"/>
+ <child link="upper_leg_back_rightR_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="lower_leg_back_rightR_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2032"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2032"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_back_rightR_link"/>
- <child link="lower_leg_back_rightR_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="upper_leg_back_rightL_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="motor_back_rightL_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_back_rightL_link"/>
- <child link="upper_leg_back_rightL_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
-
-
- <link name="lower_leg_back_rightL_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_back_rightL_link"/>
- <child link="lower_leg_back_rightL_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
-
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <mass value=".086"/>
+ <inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
+ </inertial>
+ </link>
+ <joint name="knee_back_rightR_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_back_rightR_link"/>
+ <child link="lower_leg_back_rightR_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="upper_leg_back_rightL_link">
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_back_rightL_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_back_rightL_link"/>
+ <child link="upper_leg_back_rightL_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="lower_leg_back_rightL_link">
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .1"/>
+ <mass value=".072"/>
+ <inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
+ </inertial>
+ </link>
+ <joint name="knee_back_rightL_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_back_rightL_link"/>
+ <child link="lower_leg_back_rightL_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
<link name="upper_leg_back_leftR_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="hip_leftR_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_back_leftR_link"/>
- <child link="upper_leg_back_leftR_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-<link name="lower_leg_back_leftR_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2032"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2032"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_back_leftR_link"/>
- <child link="lower_leg_back_leftR_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
- <link name="upper_leg_back_leftL_link">
- <visual>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <geometry>
- <box size=".01 0.01 .11"/>
- </geometry>
- </collision>
- <inertial>
- <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="motor_back_leftL_link" type="fixed">
- <axis xyz="0 0 1"/>
- <parent link="motor_back_leftL_link"/>
- <child link="upper_leg_back_leftL_link"/>
- <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
-
- <link name="lower_leg_back_leftL_link">
- <contact>
- <friction_anchor/>
- <stiffness value="30000.0"/>
- <damping value="1000.0"/>
- <spinning_friction value=".3"/>
- <lateral_friction value="1"/>
- </contact>
-
- <visual>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </geometry>
- <material name="grey">
- <color rgba="0.65 0.65 0.75 1"/>
- </material>
- </visual>
- <collision>
- <origin rpy="0.0 0 0" xyz="0 0 .1"/>
- <geometry>
- <box size=".01 0.01 .2"/>
- </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">
- <axis xyz="0 1 0"/>
- <parent link="upper_leg_back_leftL_link"/>
- <child link="lower_leg_back_leftL_link"/>
- <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
- <limit effort="100" velocity="100"/>
- <joint_properties damping="0.0" friction="0.0"/>
- </joint>
-
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_back_leftR_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_back_leftR_link"/>
+ <child link="upper_leg_back_leftR_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="lower_leg_back_leftR_link">
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .108"/>
+ <geometry>
+ <box size=".017 .009 .216"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .1"/>
+ <mass value=".072"/>
+ <inertia ixx=".00023166" ixy=".0" ixz=".0" iyy=".00023325" iyz=".0" izz=".00000198"/>
+ </inertial>
+ </link>
+ <joint name="knee_back_leftR_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_back_leftR_link"/>
+ <child link="lower_leg_back_leftR_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="upper_leg_back_leftL_link">
+ <visual>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <geometry>
+ <box size=".039 .008 .129"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <mass value=".034"/>
+ <inertia ixx=".000038770" ixy=".0" ixz=".0" iyy=".000042198" iyz=".0" izz=".0000036030"/>
+ </inertial>
+ </link>
+ <joint name="hip_back_leftL_joint" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="motor_back_leftL_link"/>
+ <child link="upper_leg_back_leftL_link"/>
+ <origin rpy="-1.57075 0 0" xyz="0 .045 -.0145"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
+ <link name="lower_leg_back_leftL_link">
+ <contact>
+ <friction_anchor/>
+ <stiffness value="3000.0"/>
+ <damping value="100.0"/>
+ <spinning_friction value=".3"/>
+ <lateral_friction value="1"/>
+ </contact>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ <material name="grey">
+ <color rgba=".65 .65 .75 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <geometry>
+ <box size=".017 .009 .240"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 .120"/>
+ <mass value=".086"/>
+ <inertia ixx=".00032459" ixy=".0" ixz=".0" iyy=".00032637" iyz=".0" izz=".000002178"/>
+ </inertial>
+ </link>
+ <joint name="knee_back_leftL_joint" type="continuous">
+ <axis xyz="0 1 0"/>
+ <parent link="upper_leg_back_leftL_link"/>
+ <child link="lower_leg_back_leftL_link"/>
+ <origin rpy="0 0 0" xyz="0 .0085 .056"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping=".0" friction=".0"/>
+ </joint>
</robot>
-
diff --git a/examples/pybullet/gym/pybullet_envs/examples/microtaur.py b/examples/pybullet/gym/pybullet_envs/examples/microtaur.py
index fa66814f7..2d5b843a3 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/microtaur.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/microtaur.py
@@ -161,28 +161,26 @@ for i in range(nJoints):
motor_front_rightR_joint = jointNameToId['motor_front_rightR_joint']
motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint']
-knee_front_rightL_link = jointNameToId['knee_front_rightL_link']
-hip_front_rightR_link = jointNameToId['hip_front_rightR_link']
-knee_front_rightR_link = jointNameToId['knee_front_rightR_link']
-motor_front_rightL_link = jointNameToId['motor_front_rightL_link']
+knee_front_rightL_joint = jointNameToId['knee_front_rightL_joint']
+hip_front_rightR_joint = jointNameToId['hip_front_rightR_joint']
+knee_front_rightR_joint = jointNameToId['knee_front_rightR_joint']
+motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint']
motor_front_leftR_joint = jointNameToId['motor_front_leftR_joint']
-hip_front_leftR_link = jointNameToId['hip_front_leftR_link']
-knee_front_leftR_link = jointNameToId['knee_front_leftR_link']
+hip_front_leftR_joint = jointNameToId['hip_front_leftR_joint']
+knee_front_leftR_joint = jointNameToId['knee_front_leftR_joint']
+motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint']
motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint']
-motor_front_leftL_link = jointNameToId['motor_front_leftL_link']
-knee_front_leftL_link = jointNameToId['knee_front_leftL_link']
+knee_front_leftL_joint = jointNameToId['knee_front_leftL_joint']
motor_back_rightR_joint = jointNameToId['motor_back_rightR_joint']
-hip_rightR_link = jointNameToId['hip_rightR_link']
-knee_back_rightR_link = jointNameToId['knee_back_rightR_link']
+knee_back_rightR_joint = jointNameToId['knee_back_rightR_joint']
motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint']
-motor_back_rightL_link = jointNameToId['motor_back_rightL_link']
-knee_back_rightL_link = jointNameToId['knee_back_rightL_link']
+motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint']
+knee_back_rightL_joint = jointNameToId['knee_back_rightL_joint']
motor_back_leftR_joint = jointNameToId['motor_back_leftR_joint']
-hip_leftR_link = jointNameToId['hip_leftR_link']
-knee_back_leftR_link = jointNameToId['knee_back_leftR_link']
+knee_back_leftR_joint = jointNameToId['knee_back_leftR_joint']
+motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint']
motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint']
-motor_back_leftL_link = jointNameToId['motor_back_leftL_link']
-knee_back_leftL_link = jointNameToId['knee_back_leftL_link']
+knee_back_leftL_joint = jointNameToId['knee_back_leftL_joint']
#fixtorso = p.createConstraint(-1,-1,quadruped,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,0])
@@ -230,21 +228,21 @@ if (useMaximalCoordinates):
p.setJointMotorControl2(quadruped, motor_back_rightR_joint, p.POSITION_CONTROL,
motordir[7] * halfpi * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_front_leftL_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_front_leftL_joint, p.POSITION_CONTROL,
motordir[0] * (kneeangle + twopi) * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_front_leftR_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_front_leftR_joint, p.POSITION_CONTROL,
motordir[1] * kneeangle * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_back_leftL_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_back_leftL_joint, p.POSITION_CONTROL,
motordir[2] * kneeangle * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_back_leftR_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_back_leftR_joint, p.POSITION_CONTROL,
motordir[3] * (kneeangle + twopi) * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_front_rightL_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_front_rightL_joint, p.POSITION_CONTROL,
motordir[4] * (kneeangle) * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_front_rightR_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_front_rightR_joint, p.POSITION_CONTROL,
motordir[5] * (kneeangle + twopi) * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_back_rightL_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_back_rightL_joint, p.POSITION_CONTROL,
motordir[6] * (kneeangle + twopi) * float(aa) / steps)
- p.setJointMotorControl2(quadruped, knee_back_rightR_link, p.POSITION_CONTROL,
+ p.setJointMotorControl2(quadruped, knee_back_rightR_joint, p.POSITION_CONTROL,
motordir[7] * kneeangle * float(aa) / steps)
p.stepSimulation()
@@ -252,57 +250,57 @@ if (useMaximalCoordinates):
else:
p.resetJointState(quadruped, motor_front_leftL_joint, motordir[0] * halfpi)
- p.resetJointState(quadruped, knee_front_leftL_link, motordir[0] * kneeangle)
+ p.resetJointState(quadruped, knee_front_leftL_joint, motordir[0] * kneeangle)
p.resetJointState(quadruped, motor_front_leftR_joint, motordir[1] * halfpi)
- p.resetJointState(quadruped, knee_front_leftR_link, motordir[1] * kneeangle)
+ p.resetJointState(quadruped, knee_front_leftR_joint, motordir[1] * kneeangle)
p.resetJointState(quadruped, motor_back_leftL_joint, motordir[2] * halfpi)
- p.resetJointState(quadruped, knee_back_leftL_link, motordir[2] * kneeangle)
+ p.resetJointState(quadruped, knee_back_leftL_joint, motordir[2] * kneeangle)
p.resetJointState(quadruped, motor_back_leftR_joint, motordir[3] * halfpi)
- p.resetJointState(quadruped, knee_back_leftR_link, motordir[3] * kneeangle)
+ p.resetJointState(quadruped, knee_back_leftR_joint, motordir[3] * kneeangle)
p.resetJointState(quadruped, motor_front_rightL_joint, motordir[4] * halfpi)
- p.resetJointState(quadruped, knee_front_rightL_link, motordir[4] * kneeangle)
+ p.resetJointState(quadruped, knee_front_rightL_joint, motordir[4] * kneeangle)
p.resetJointState(quadruped, motor_front_rightR_joint, motordir[5] * halfpi)
- p.resetJointState(quadruped, knee_front_rightR_link, motordir[5] * kneeangle)
+ p.resetJointState(quadruped, knee_front_rightR_joint, motordir[5] * kneeangle)
p.resetJointState(quadruped, motor_back_rightL_joint, motordir[6] * halfpi)
- p.resetJointState(quadruped, knee_back_rightL_link, motordir[6] * kneeangle)
+ p.resetJointState(quadruped, knee_back_rightL_joint, motordir[6] * kneeangle)
p.resetJointState(quadruped, motor_back_rightR_joint, motordir[7] * halfpi)
- p.resetJointState(quadruped, knee_back_rightR_link, motordir[7] * kneeangle)
+ p.resetJointState(quadruped, knee_back_rightR_joint, motordir[7] * kneeangle)
#p.getNumJoints(1)
if (toeConstraint):
- cid = p.createConstraint(quadruped, knee_front_leftR_link, quadruped, knee_front_leftL_link,
+ cid = p.createConstraint(quadruped, knee_front_leftR_joint, quadruped, knee_front_leftL_joint,
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
p.changeConstraint(cid, maxForce=maxKneeForce)
- cid = p.createConstraint(quadruped, knee_front_rightR_link, quadruped, knee_front_rightL_link,
+ cid = p.createConstraint(quadruped, knee_front_rightR_joint, quadruped, knee_front_rightL_joint,
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
p.changeConstraint(cid, maxForce=maxKneeForce)
- cid = p.createConstraint(quadruped, knee_back_leftR_link, quadruped, knee_back_leftL_link,
+ cid = p.createConstraint(quadruped, knee_back_leftR_joint, quadruped, knee_back_leftL_joint,
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
p.changeConstraint(cid, maxForce=maxKneeForce)
- cid = p.createConstraint(quadruped, knee_back_rightR_link, quadruped, knee_back_rightL_link,
+ cid = p.createConstraint(quadruped, knee_back_rightR_joint, quadruped, knee_back_rightL_joint,
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
p.changeConstraint(cid, maxForce=maxKneeForce)
if (1):
- p.setJointMotorControl(quadruped, knee_front_leftL_link, p.VELOCITY_CONTROL, 0,
+ p.setJointMotorControl(quadruped, knee_front_leftL_joint, p.VELOCITY_CONTROL, 0,
kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_front_leftR_link, p.VELOCITY_CONTROL, 0,
+ p.setJointMotorControl(quadruped, knee_front_leftR_joint, p.VELOCITY_CONTROL, 0,
kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_front_rightL_link, p.VELOCITY_CONTROL, 0,
+ p.setJointMotorControl(quadruped, knee_front_rightL_joint, p.VELOCITY_CONTROL, 0,
kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_front_rightR_link, p.VELOCITY_CONTROL, 0,
+ p.setJointMotorControl(quadruped, knee_front_rightR_joint, p.VELOCITY_CONTROL, 0,
kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_back_leftL_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_back_leftR_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_back_leftL_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_back_leftR_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_back_rightL_link, p.VELOCITY_CONTROL, 0,
+ p.setJointMotorControl(quadruped, knee_back_leftL_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
+ p.setJointMotorControl(quadruped, knee_back_leftR_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
+ p.setJointMotorControl(quadruped, knee_back_leftL_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
+ p.setJointMotorControl(quadruped, knee_back_leftR_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
+ p.setJointMotorControl(quadruped, knee_back_rightL_joint, p.VELOCITY_CONTROL, 0,
kneeFrictionForce)
- p.setJointMotorControl(quadruped, knee_back_rightR_link, p.VELOCITY_CONTROL, 0,
+ p.setJointMotorControl(quadruped, knee_back_rightR_joint, p.VELOCITY_CONTROL, 0,
kneeFrictionForce)
p.setGravity(0, 0, -10)
@@ -376,7 +374,7 @@ p.setJointMotorControl2(bodyIndex=quadruped,
p.setRealTimeSimulation(useRealTime)
t = 0.0
-t_end = t + 115
+t_end = t + 5
ref_time = time.time()
while (t < t_end):
p.setGravity(0, 0, -10)