summaryrefslogtreecommitdiff
path: root/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf
diff options
context:
space:
mode:
Diffstat (limited to 'examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf')
-rw-r--r--examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf1428
1 files changed, 1428 insertions, 0 deletions
diff --git a/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf b/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf
new file mode 100644
index 000000000..6dcdf6f42
--- /dev/null
+++ b/examples/pybullet/gym/pybullet_data/quadruped/microtaur/microtaur.urdf
@@ -0,0 +1,1428 @@
+<?xml version="0.0" ?>
+<!-- ======================================================================= -->
+<!--LICENSE: -->
+<!--Copyright (c) 2019, Erwin Coumans -->
+<!--Google Inc. -->
+<!--All rights reserved. -->
+<!-- -->
+<!--Redistribution and use in source and binary forms, with or without -->
+<!--modification, are permitted provided that the following conditions are -->
+<!--met: -->
+<!-- -->
+<!--1. Redistributions or derived work must retain this copyright notice, -->
+<!-- this list of conditions and the following disclaimer. -->
+<!-- -->
+<!--2. Redistributions in binary form must reproduce the above copyright -->
+<!-- notice, this list of conditions and the following disclaimer in the -->
+<!-- documentation and/or other materials provided with the distribution. -->
+<!-- -->
+<!--THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS -->
+<!--IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,-->
+<!--THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -->
+<!--PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR -->
+<!--CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, -->
+<!--EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -->
+<!--PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR -->
+<!--PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF -->
+<!--LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING -->
+<!--NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -->
+<!--SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -->
+
+<robot name="microtaur">
+ <link name="base_chassis_link">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 -1.57079" xyz="0 0 0.036"/>
+ <mass value="0.64"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 -1.57079" xyz="-0.045 0.045 0.018"/>
+ <geometry>
+ <mesh filename="xavier.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba="0.3 0.3 0.3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 -1.57079" xyz="0 0 0.033"/>
+ <geometry>
+ <box size="0.092 0.105 0.045"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <link name="plate0">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.08"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="-0.037 0.0045 0"/>
+ <geometry>
+ <mesh filename="plate.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black1">
+ <color rgba="0.1 0.1 0.1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.074 0.009 0.138"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="plate0_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="plate0"/>
+ <origin rpy="-1.57079 0 -1.57079" xyz="0.063 0.028 0.005"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+ <link name="plate1">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.08"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="-0.037 0.0045 0"/>
+ <geometry>
+ <mesh filename="plate.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black1">
+ <color rgba="0.1 0.1 0.1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.074 0.009 0.138"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="plate1_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="plate1"/>
+ <origin rpy="-1.57079 0 -1.57079" xyz="-0.063 0.028 0.005"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+ <link name="plate2">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.08"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="-0.037 0.0045 0"/>
+ <geometry>
+ <mesh filename="plate.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black1">
+ <color rgba="0.1 0.1 0.1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.074 0.009 0.138"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="plate2_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="plate2"/>
+ <origin rpy="-1.57079 0 1.57079" xyz="0.063 -0.028 0.005"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+ <link name="plate3">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.08"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="-0.037 0.0045 0"/>
+ <geometry>
+ <mesh filename="plate.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black1">
+ <color rgba="0.1 0.1 0.1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.074 0.009 0.138"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="plate3_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="plate3"/>
+ <origin rpy="-1.57079 0 1.57079" xyz="-0.063 -0.028 0.005"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+
+ <link name="chassis_right">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="-1.57079 0 -1.57079" xyz="0 0 0"/>
+ <mass value="0.13"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="-1.57079 0 -1.57079" xyz="-0.1502 0.019 0.019 "/>
+ <geometry>
+ <mesh filename="channel.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="white">
+ <color rgba="1 1 1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="-1.57079 0 -1.57079" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.038 0.038 0.305"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="chassis_right_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="chassis_right"/>
+ <origin rpy="0 0 0" xyz="0.0 -0.0955 0.019"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+ <link name="chassis_front">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="-1.57079 0 0" xyz="0 0 0"/>
+ <mass value="0.13"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="-1.57079 0 0" xyz="-0.019 -0.1502 0.019 "/>
+ <geometry>
+ <mesh filename="channel.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="bla">
+ <color rgba="1 1 1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="-1.57079 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.038 0.038 0.305"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="chassis_front_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="chassis_front"/>
+ <origin rpy="0 0 0" xyz="0.1335 0.0 -0.019"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+ <link name="dynamixel4">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel4_chassis_front" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_front"/>
+ <child link="dynamixel4"/>
+ <origin rpy="-1.57079 0 3.141592" xyz="0 0.135 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+<link name="dynamixel12">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel12_chassis_front" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_front"/>
+ <child link="dynamixel12"/>
+ <origin rpy="-1.57079 0 0" xyz="0 0.055 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+ <link name="dynamixel3">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel3_chassis_front" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_front"/>
+ <child link="dynamixel3"/>
+ <origin rpy="-1.57079 0 0" xyz="0 -0.135 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+<link name="dynamixel5">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel5_chassis_front" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_front"/>
+ <child link="dynamixel5"/>
+ <origin rpy="-1.57079 0 3.141592" xyz="0 -0.055 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+ <link name="dynamixel8">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel8_chassis_rear" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_rear"/>
+ <child link="dynamixel8"/>
+ <origin rpy="-1.57079 0 3.141592" xyz="0 0.135 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+<link name="dynamixel10">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel10_chassis_rear" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_rear"/>
+ <child link="dynamixel10"/>
+ <origin rpy="-1.57079 0 0" xyz="0 0.055 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+ <link name="dynamixel13">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel13_chassis_rear" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_rear"/>
+ <child link="dynamixel13"/>
+ <origin rpy="-1.57079 0 0" xyz="0 -0.135 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+<link name="dynamixel7">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel7_chassis_rear" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_rear"/>
+ <child link="dynamixel7"/>
+ <origin rpy="-1.57079 0 3.141592" xyz="0 -0.055 -0.03"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+ <link name="dynamixel9">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.082"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0.011 0"/>
+ <geometry>
+ <mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="black">
+ <color rgba=".3 .3 .3 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.024 0.047 0.034"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="dynamixel9_chassis_front" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="chassis_front"/>
+ <child link="dynamixel9"/>
+ <origin rpy="1.57079 0 0" xyz="0 0 0.042"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+ <link name="d435">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="0.081"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0.0125"/>
+ <geometry>
+ <mesh filename="d435i.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="white">
+ <color rgba="1 1 1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.09 0.025 0.025"/>
+ </geometry>
+ </collision>
+ </link>
+
+
+ <joint name="d435_dynamixel9" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="dynamixel9"/>
+ <child link="d435"/>
+ <origin rpy="0 1.57079 0" xyz="0 0.04 0"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+ <link name="chassis_rear">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="-1.57079 0 0" xyz="0 0 0"/>
+ <mass value="0.13"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="-1.57079 0 0" xyz="-0.019 -0.1502 0.019 "/>
+ <geometry>
+ <mesh filename="channel.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="white">
+ <color rgba="1 1 1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="-1.57079 0 0" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.038 0.038 0.305"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="chassis_rear_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="chassis_rear"/>
+ <origin rpy="0 0 0" xyz="-0.1335 0.0 -0.019"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+ <link name="chassis_left">
+ <contact>
+ <lateral_friction value="0.3"/>
+ </contact>
+ <inertial>
+ <origin rpy="-1.57079 0 -1.57079" xyz="0 0 0"/>
+ <mass value="0.13"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <origin rpy="-1.57079 0 -1.57079" xyz="-0.1502 0.019 0.019 "/>
+ <geometry>
+ <mesh filename="channel.stl" scale="1.0 1.0 1.0"/>
+ </geometry>
+ <material name="white">
+ <color rgba="1 1 1 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="-1.57079 0 -1.57079" xyz="0 0 0"/>
+ <geometry>
+ <box size="0.038 0.038 0.305"/>
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="chassis_left_center" type="fixed">
+ <axis xyz="0 0 1"/>
+ <parent link="base_chassis_link"/>
+ <child link="chassis_left"/>
+ <origin rpy="0 0 0" xyz="0.0 0.0955 0.019"/>
+ <limit effort="100" velocity="100"/>
+ <joint_properties damping="0.0" friction="0.0"/>
+ </joint>
+
+
+
+ <link name="motor_front_rightR_link">
+
+ <visual>
+ <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>
+
+
+ <link name="motor_front_rightL_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_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>
+ <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>
+
+
+ <link name="motor_front_leftR_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_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>
+ <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>
+
+
+ <link name="motor_back_rightL_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_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>
+ <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>
+
+
+ <link name="motor_back_leftR_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_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>
+
+ <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>
+
+ <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>
+
+
+ <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>
+
+
+ <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>
+
+ <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>
+
+ <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>
+
+
+
+ <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>
+
+</robot>
+