diff --git a/tor_description/meshes/v2/ankle_X_collision.stl b/tor_description/meshes/v2/ankle_X_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..b3558adca54cd6c02a5be0d15e27915aac3bf880
Binary files /dev/null and b/tor_description/meshes/v2/ankle_X_collision.stl differ
diff --git a/tor_description/meshes/v2/ankle_X_lo_res.stl b/tor_description/meshes/v2/ankle_X_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..b955dd77bb3af8f857c266a88699f63546ecfb37
Binary files /dev/null and b/tor_description/meshes/v2/ankle_X_lo_res.stl differ
diff --git a/tor_description/meshes/v2/ankle_Y_collision.stl b/tor_description/meshes/v2/ankle_Y_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..f6722db80d13bacccb5ae79482c47eca084ab512
Binary files /dev/null and b/tor_description/meshes/v2/ankle_Y_collision.stl differ
diff --git a/tor_description/meshes/v2/ankle_Y_lo_res.stl b/tor_description/meshes/v2/ankle_Y_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..eeafe5f9300e9eaa7c6ae950a3d86caeca8a1029
Binary files /dev/null and b/tor_description/meshes/v2/ankle_Y_lo_res.stl differ
diff --git a/tor_description/meshes/v2/base_link_collision.stl b/tor_description/meshes/v2/base_link_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..2d5d0fae2180a115eb73036ca0656270a423204f
Binary files /dev/null and b/tor_description/meshes/v2/base_link_collision.stl differ
diff --git a/tor_description/meshes/v2/base_link_lo_res.stl b/tor_description/meshes/v2/base_link_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..2d5d0fae2180a115eb73036ca0656270a423204f
Binary files /dev/null and b/tor_description/meshes/v2/base_link_lo_res.stl differ
diff --git a/tor_description/meshes/v2/hip_x_collision.stl b/tor_description/meshes/v2/hip_x_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..bad9cc0b1636bd61c55edf0b7ad6977a80dfba36
Binary files /dev/null and b/tor_description/meshes/v2/hip_x_collision.stl differ
diff --git a/tor_description/meshes/v2/hip_x_lo_res.stl b/tor_description/meshes/v2/hip_x_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..09d2c75ade92ccf468ce525e2c9d1b14094cd0e0
Binary files /dev/null and b/tor_description/meshes/v2/hip_x_lo_res.stl differ
diff --git a/tor_description/meshes/v2/hip_y_collision.stl b/tor_description/meshes/v2/hip_y_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..03a3f54ab811000f6172a7dc14736884eeba7ef2
Binary files /dev/null and b/tor_description/meshes/v2/hip_y_collision.stl differ
diff --git a/tor_description/meshes/v2/hip_y_lo_res.stl b/tor_description/meshes/v2/hip_y_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..2ea1a4f753a286cf465f009a5e3705855cfe0d31
Binary files /dev/null and b/tor_description/meshes/v2/hip_y_lo_res.stl differ
diff --git a/tor_description/meshes/v2/hip_z_collision.stl b/tor_description/meshes/v2/hip_z_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..854afb30dd0754dc40eb5023b937191a10b5ce37
Binary files /dev/null and b/tor_description/meshes/v2/hip_z_collision.stl differ
diff --git a/tor_description/meshes/v2/hip_z_lo_res.stl b/tor_description/meshes/v2/hip_z_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..62ba1ab2bc58626a498b7fa869e68b743095ff81
Binary files /dev/null and b/tor_description/meshes/v2/hip_z_lo_res.stl differ
diff --git a/tor_description/meshes/v2/knee_collision.stl b/tor_description/meshes/v2/knee_collision.stl
new file mode 100644
index 0000000000000000000000000000000000000000..e18ec28d80eb14b700589ada94ec6bbf0f4e7f99
Binary files /dev/null and b/tor_description/meshes/v2/knee_collision.stl differ
diff --git a/tor_description/meshes/v2/knee_lo_res.stl b/tor_description/meshes/v2/knee_lo_res.stl
new file mode 100644
index 0000000000000000000000000000000000000000..55ab0f11ed8bf0852357529cd9f53e45e70e638d
Binary files /dev/null and b/tor_description/meshes/v2/knee_lo_res.stl differ
diff --git a/tor_description/robots/tor_lower_body_v1.urdf.xacro b/tor_description/robots/tor_lower_body_v1.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..5cc159c94dea7999e9043ba4cd968d291916f522
--- /dev/null
+++ b/tor_description/robots/tor_lower_body_v1.urdf.xacro
@@ -0,0 +1,59 @@
+<?xml version="1.0"?>
+<!--
+
+  Copyright (c) 2014, PAL Robotics, S.L.
+  All rights reserved.
+
+  This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License.
+  To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to
+  Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA.
+-->
+<robot name="tor" xmlns:xacro="http://www.ros.org/wiki/xacro"
+        xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+        xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+        xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
+
+
+  <xacro:include filename="$(find tor_description)/urdf/leg/leg.urdf.xacro" />
+
+    <link name="base_link">
+      <inertial>
+        <origin xyz="0.0 0.0 0.36" rpy="0 0 0"/>
+        <mass value="34.0" />
+         <inertia ixx="0.529688470"  ixy="0.0"  ixz="0.0" iyy="0.34860507904" iyz="0.0" izz="0.23865908621" />
+      </inertial>
+
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/torso_dummy.stl" scale="1 1 1"/>
+        </geometry>
+      </visual>
+      
+      <collision>
+       <origin rpy="0 0 0" xyz="0 0 0.05"/>
+	    <geometry>
+           <box size="0.1 0.3 0.1"/>
+        </geometry>
+      </collision>  
+
+     </link>
+     
+     
+   <xacro:tor_leg prefix="left"  reflect="1" />
+   <xacro:tor_leg prefix="right" reflect="-1" />
+
+  <!-- Generic simulator_gazebo plugins -->
+  <xacro:include filename="$(find tor_description)/gazebo/gazebo.urdf.xacro" />
+  <!-- Materials for visualization -->
+  <xacro:include filename="$(find tor_description)/urdf/materials.urdf.xacro" />
+  
+  
+  <xacro:include filename="$(find tor_description)/urdf/sensors/imu.urdf.xacro" />
+  
+    <!-- imu -->
+  <xacro:tor_imu name="imu" parent="base_link" update_rate="100.0">
+    <origin xyz="0 0 0" rpy="0 0 0"/>
+  </xacro:tor_imu>
+
+</robot>
diff --git a/tor_description/robots/tor_lower_body_v2.urdf.xacro b/tor_description/robots/tor_lower_body_v2.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..752c08bd418bb1d15bc19b93ed7083adbbd63011
--- /dev/null
+++ b/tor_description/robots/tor_lower_body_v2.urdf.xacro
@@ -0,0 +1,51 @@
+<?xml version="1.0"?>
+<!--
+
+  Copyright (c) 2014, PAL Robotics, S.L.
+  All rights reserved.
+
+  This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivs 3.0 Unported License.
+  To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-nd/3.0/ or send a letter to
+  Creative Commons, 444 Castro Street, Suite 900, Mountain View, California, 94041, USA.
+-->
+<robot name="tor" xmlns:xacro="http://www.ros.org/wiki/xacro"
+        xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+        xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+        xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
+
+  <xacro:include filename="$(find tor_description)/urdf/leg/leg_v2.urdf.xacro" />
+    <link name="base_link">
+      <inertial>
+        <origin xyz="-0.06071 0.00861 0.06368" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="13.34865"/>
+        <inertia ixx="0.06652900000" ixy="-0.00035700000" ixz="0.00027600000"
+                 iyy="0.03746500000" iyz="-0.00125400000"
+                 izz="0.07895100000"/>
+      </inertial>
+
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/base_link_lo_res.stl" scale="1 1 1"/>
+        </geometry>
+        <material name="DarkGrey" />
+      </visual>
+      
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/base_link_collision.stl" scale="1 1 1"/>
+        </geometry>
+      </collision>  
+    </link>
+     
+     
+   <xacro:tor_leg prefix="left"  reflect="1" />
+   <xacro:tor_leg prefix="right" reflect="-1" />
+
+  <!-- Generic simulator_gazebo plugins -->
+  <xacro:include filename="$(find tor_description)/gazebo/gazebo.urdf.xacro" />
+  <!-- Materials for visualization -->
+  <xacro:include filename="$(find tor_description)/urdf/materials.urdf.xacro" />
+
+</robot>
diff --git a/tor_description/robots/upload_legs_v2.launch b/tor_description/robots/upload_legs_v2.launch
new file mode 100644
index 0000000000000000000000000000000000000000..87688ef3ee2232558837a188ed64840cf4c574a0
--- /dev/null
+++ b/tor_description/robots/upload_legs_v2.launch
@@ -0,0 +1,8 @@
+<launch>
+
+  <arg name="robot" default="titanium"/>
+
+  <!-- Robot description -->
+  <param name="robot_description" command="$(find xacro)/xacro.py '$(find tor_description)/robots/tor_lower_body_v2.urdf.xacro'" />
+
+</launch>
diff --git a/tor_description/urdf/leg/leg.urdf.xacro b/tor_description/urdf/leg/leg.urdf.xacro
index f36de3ea0d19ff3baf9f3b880261a29835adb219..63219ec0c74f2c1530ceda020d4991808f3d2586 100644
--- a/tor_description/urdf/leg/leg.urdf.xacro
+++ b/tor_description/urdf/leg/leg.urdf.xacro
@@ -168,7 +168,12 @@
       <!-- nominal -->
       <!-- <limit lower="-0.5236" upper="1.571" effort="49" velocity="3.87" /> -->
       <!-- peak -->   
-      <limit lower="-0.5236" upper="1.571" effort="100" velocity="3.87" />
+      <xacro:if value="${reflect == 1}">
+        <limit lower="-0.5236" upper="1.571" effort="100" velocity="3.87" />
+      </xacro:if>
+      <xacro:if value="${reflect == -1}">
+        <limit lower="-1.571" upper="0.5236" effort="100" velocity="3.87" />
+      </xacro:if>
       <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
      </joint>
 
diff --git a/tor_description/urdf/leg/leg_v2.urdf.xacro b/tor_description/urdf/leg/leg_v2.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..5038f7f2b0c61cd66f021f1fdb4d074eeb412d18
--- /dev/null
+++ b/tor_description/urdf/leg/leg_v2.urdf.xacro
@@ -0,0 +1,325 @@
+<?xml version="1.0"?>
+
+<robot xmlns:xacro="http://ros.org/wiki/xacro" name="tor">
+
+  <xacro:include filename="$(find tor_description)/urdf/leg/leg.transmission.xacro" />
+
+  <xacro:property name="deg_to_rad"       value="0.01745329251994329577" />
+  <xacro:property name="eps_radians"      value="0.008" /> <!-- 0.45deg -->
+  <xacro:property name="eps_meters"       value="0.005" />
+  <xacro:property name="leg_reduction"    value="1.0" />
+  <xacro:property name="leg_friction"     value="0.0" />
+  <xacro:property name="leg_damping"      value="0.0" />
+
+
+  <xacro:macro name="tor_leg" params="prefix reflect">
+    <!-- Joint hip_z (mesh link) : child link hip_x -> parent link base_link -->
+
+    <link name="leg_${prefix}_1_link">
+      <inertial>
+        <origin xyz="0.02320 -0.00009 0.04949" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="1.88569"/>
+        <inertia ixx="0.00384800000" ixy="0.00003200000" ixz="-0.00082600000"
+                 iyy="0.00599400000" iyz="0.00007800000"
+                 izz="0.00322200000"/>
+      </inertial>
+
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/hip_z_lo_res.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+        <material name="DarkGrey" />
+      </visual>
+
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+           <mesh filename="package://tor_description/meshes/v2/hip_z_collision.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+      </collision>  
+    </link>
+
+    <joint name="leg_${prefix}_1_joint" type="revolute">
+      <parent link="base_link"/>
+      <child link="leg_${prefix}_1_link"/>
+      <origin xyz="0.00000 ${reflect*0.08500} -0.14200" 
+              rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
+      <axis xyz="0 0 1" />
+     <xacro:if value="${reflect == 1}">
+        <limit lower="-0.5236" upper="1.571" effort="100" velocity="3.87" />
+      </xacro:if>
+      <xacro:if value="${reflect == -1}">
+        <limit lower="-1.571" upper="0.5236" effort="100" velocity="3.87" />
+      </xacro:if>
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint>
+
+
+    <!-- Joint hip_x (mesh link) : child link hip_y -> parent link hip_z -->
+
+    <link name="leg_${prefix}_2_link">
+      <inertial>
+        <origin xyz="0.01583 -0.00021 0.00619" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="2.37607"/>
+        <inertia ixx="0.00342100000" ixy="-0.00011300000" ixz="-0.00022500000"
+                 iyy="0.00402400000" iyz="-0.00003100000"
+                 izz="0.00416400000"/>
+      </inertial>
+
+      <visual>
+        <origin xyz="0 0 0.0" rpy="0  0  0" />
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/hip_x_lo_res.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+        <material name="DarkGrey" />
+      </visual>
+
+      <collision>
+      <origin xyz="0 0 0.0" rpy="0  0  0" />
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/hip_x_collision.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="leg_${prefix}_2_joint" type="revolute">
+      <parent link="leg_${prefix}_1_link"/>
+      <child link="leg_${prefix}_2_link"/>
+      <origin xyz="0.00000 0.00000 0.00000" 
+              rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
+      <axis xyz="1 0 0" />
+      <limit lower="-0.524" upper="0.5236" effort="160" velocity="5.8" />
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint>
+
+    <!-- Joint hip_y (mesh link) : child link knee -> parent link hip_x -->
+
+    <link name="leg_${prefix}_3_link">
+      <inertial>
+        <origin xyz="0.00658 ${reflect*0.06563} -0.17278" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="6.82734"/>
+        <inertia ixx="0.12390600000" ixy="${reflect*-0.00041200000}" ixz="-0.00205900000"
+                 iyy="0.10844700000" iyz="${reflect*0.01672500000}"
+                 izz="0.02781200000"/>
+      </inertial>
+
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/hip_y_lo_res.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+        <material name="DarkGrey" />
+      </visual>
+
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+           <mesh filename="package://tor_description/meshes/v2/hip_y_collision.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+      </collision>  
+    </link>
+
+    <joint name="leg_${prefix}_3_joint" type="revolute">
+      <parent link="leg_${prefix}_2_link"/>
+      <child link="leg_${prefix}_3_link"/>
+      <origin xyz="0.00000 0.00000 0.00000" 
+              rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
+      <axis xyz="0 1 0" />
+      <limit lower="-2.095" upper="0.7" effort="160" velocity="5.8" />
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint>
+
+    <!-- Joint knee (mesh link) : child link ankle_y -> parent link hip_y -->
+
+    <link name="leg_${prefix}_4_link">
+      <inertial>
+        <origin xyz="0.01520 ${reflect*0.02331} -0.12063" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="3.63668"/>
+        <inertia ixx="0.03531500000" ixy="${reflect*0.00002900000}" ixz="-0.00016600000"
+                 iyy="0.02933600000" iyz="${reflect*-0.00130500000}"
+                 izz="0.01174000000"/>
+      </inertial>
+
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/knee_lo_res.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+        <material name="DarkGrey" />
+      </visual>
+
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+           <mesh filename="package://tor_description/meshes/v2/knee_collision.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+      </collision>  
+    </link>
+
+    <joint name="leg_${prefix}_4_joint" type="revolute">
+      <parent link="leg_${prefix}_3_link"/>
+      <child link="leg_${prefix}_4_link"/>
+      
+      <origin xyz="0.00000 0.00000 -0.38000" 
+              rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> 
+      <axis xyz="0 1 0" />
+      <limit lower="0" upper="2.618" effort="300" velocity="7" />
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint>
+
+    <!-- Joint ankle_y (mesh link) : child link ankle_x -> parent link knee -->
+
+    <link name="leg_${prefix}_5_link">
+      <inertial>
+        <origin xyz="-0.01106 ${reflect*0.04708} 0.05271" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="1.24433"/>
+        <inertia ixx="0.01148700000" ixy="${reflect*-0.00068600000}" ixz="-0.00052600000"
+                 iyy="0.00952600000" iyz="${reflect*0.00263300000}"
+                 izz="0.00390800000"/>
+      </inertial>
+
+      <visual>
+        <origin xyz="0 0 0.0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/ankle_Y_lo_res.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+        <material name="Grey" />
+      </visual>
+      
+      <collision>
+        <origin xyz="0 0 0.0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/ankle_Y_collision.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+      </collision>  
+    </link>
+
+    <joint name="leg_${prefix}_5_joint" type="revolute">
+      <parent link="leg_${prefix}_4_link"/>
+      <child link="leg_${prefix}_5_link"/>
+      <origin xyz="0.00000 0.00000 -0.32500" 
+              rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
+      <axis xyz="0 1 0" />
+      <limit lower="-1.309" upper="0.768" effort="160" velocity="5.8" />
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint>
+
+    <!-- Joint ankle_x (mesh link) : child link None -> parent link ankle_y -->
+
+    <link name="leg_${prefix}_6_link">
+      <inertial>
+        <origin xyz="-0.02087 -0.00019 -0.06059" rpy="0.00000 0.00000 0.00000"/>
+        <mass value="1.59457"/>
+        <inertia ixx="0.00383800000" ixy="0.00001600000" ixz="-0.00104100000"
+                 iyy="0.00657200000" iyz="-0.00001700000"
+                 izz="0.00504400000"/>
+      </inertial>
+
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/ankle_X_lo_res.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+        <material name="Grey" />
+      </visual>
+
+      <collision>
+        <origin xyz="0 0 0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://tor_description/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/>
+        </geometry>
+      </collision> 
+    </link>
+
+    <joint name="leg_${prefix}_6_joint" type="revolute">
+      <parent link="leg_${prefix}_5_link"/>
+      <child link="leg_${prefix}_6_link"/>
+      <origin xyz="0.00000 0.00000 0.00000" 
+              rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
+      <axis xyz="1 0 0" />
+      <limit lower="-0.524" upper="0.524" effort="100" velocity="4.8" />
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint>
+ 
+  <!-- from here is copy paste -->
+
+    <link name="${prefix}_sole_link">
+      <inertial>
+        <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
+        <mass value="0.01" />
+         <inertia ixx="0.0001"  ixy="0.0"  ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001" />
+      </inertial>
+     </link> 
+
+     <joint name="leg_${prefix}_sole_fix_joint" type="fixed">
+      <parent link="leg_${prefix}_6_link" />
+      <child link="${prefix}_sole_link" />
+      <origin xyz="0.00 0.00 -0.107" rpy="0 0 0" />
+      <axis xyz="1 0 0" />
+      <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
+    </joint> 
+    
+    <xacro:tor_leg_simple_transmission side="${prefix}" number="1" reduction="${leg_reduction}" />
+    <xacro:tor_leg_simple_transmission side="${prefix}" number="2" reduction="${leg_reduction}" />
+    <xacro:tor_leg_simple_transmission side="${prefix}" number="3" reduction="${leg_reduction}" />
+    <xacro:tor_leg_simple_transmission side="${prefix}" number="4" reduction="${leg_reduction}" />
+    <xacro:tor_leg_simple_transmission side="${prefix}" number="5" reduction="${leg_reduction}" />
+    <xacro:tor_leg_simple_transmission side="${prefix}" number="6" reduction="${leg_reduction}" />
+    
+   <gazebo reference="leg_${prefix}_1_link">
+     <mu1>0.9</mu1>
+     <mu2>0.9</mu2>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_2_link">
+     <mu1>0.9</mu1>
+     <mu2>0.9</mu2>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_3_link">
+     <mu1>0.9</mu1>
+     <mu2>0.9</mu2>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_4_link">
+     <mu1>0.9</mu1>
+     <mu2>0.9</mu2>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_5_link">
+     <mu1>0.9</mu1>
+     <mu2>0.9</mu2>
+   </gazebo>
+   
+   <!-- contact model for foot surface -->
+   <gazebo reference="leg_${prefix}_6_link">
+     <kp>1000000.0</kp>
+     <kd>100.0</kd>
+     <mu1>1.0</mu1>
+     <mu2>1.0</mu2>
+     <fdir1>0 0 1</fdir1>
+     <maxVel>1.0</maxVel>
+     <minDepth>0.003</minDepth>
+     <implicitSpringDamper>1</implicitSpringDamper>
+   </gazebo>
+
+   <gazebo reference="leg_${prefix}_1_joint">
+      <implicitSpringDamper>0.1</implicitSpringDamper>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_2_joint">
+      <implicitSpringDamper>0.1</implicitSpringDamper>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_3_joint">
+      <implicitSpringDamper>0.1</implicitSpringDamper>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_4_joint">
+      <implicitSpringDamper>0.1</implicitSpringDamper>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_5_joint">
+      <implicitSpringDamper>0.1</implicitSpringDamper>
+   </gazebo>
+   <gazebo reference="leg_${prefix}_6_joint">
+     <implicitSpringDamper>0.1</implicitSpringDamper>
+     <provideFeedback>1</provideFeedback>
+   </gazebo>
+
+ </xacro:macro>
+   
+</robot>