diff --git a/tor_description/robots/tor_lower_body.urdf.xacro b/tor_description/robots/tor_lower_body.urdf.xacro
index 752c08bd418bb1d15bc19b93ed7083adbbd63011..5cc159c94dea7999e9043ba4cd968d291916f522 100644
--- a/tor_description/robots/tor_lower_body.urdf.xacro
+++ b/tor_description/robots/tor_lower_body.urdf.xacro
@@ -13,31 +13,31 @@
         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" />
+
+  <xacro:include filename="$(find tor_description)/urdf/leg/leg.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"/>
+        <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/v2/base_link_lo_res.stl" scale="1 1 1"/>
+          <mesh filename="package://tor_description/meshes/torso_dummy.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"/>
+       <origin rpy="0 0 0" xyz="0 0 0.05"/>
+	    <geometry>
+           <box size="0.1 0.3 0.1"/>
         </geometry>
       </collision>  
-    </link>
+
+     </link>
      
      
    <xacro:tor_leg prefix="left"  reflect="1" />
@@ -47,5 +47,13 @@
   <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/urdf/leg/leg_v2.urdf.xacro b/tor_description/urdf/leg/leg_v2.urdf.xacro
index a28438fae4b10f704428b94edb96622b7ebc76ed..5038f7f2b0c61cd66f021f1fdb4d074eeb412d18 100644
--- a/tor_description/urdf/leg/leg_v2.urdf.xacro
+++ b/tor_description/urdf/leg/leg_v2.urdf.xacro
@@ -46,10 +46,12 @@
       <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" />
-      <!-- trick to use reflect (left=1, right=-1) 
-           to make ranges -30 to 90 and -90 to 30 respectively
-           as (reflect-1.0) will be either 0.0 or -2.0 -->
-      <limit lower="${(-30.0 + (reflect-1.0)*30.0) * deg_to_rad}" upper="${(90.0 + (reflect-1.0)*30.0) * deg_to_rad}" effort="160" velocity="5.8"/>
+     <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>
 
@@ -87,7 +89,7 @@
       <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="${reflect*-30.00000 * deg_to_rad}" upper="${reflect*30.00000 * deg_to_rad}" effort="160" velocity="5.8"/>
+      <limit lower="-0.524" upper="0.5236" effort="160" velocity="5.8" />
       <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
     </joint>
 
@@ -124,7 +126,7 @@
       <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="${-120.00000 * deg_to_rad}" upper="${45.00000 * deg_to_rad}" effort="160" velocity="5.8"/>
+      <limit lower="-2.095" upper="0.7" effort="160" velocity="5.8" />
       <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
     </joint>
 
@@ -162,7 +164,7 @@
       <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.00000 * deg_to_rad}" upper="${150.00000 * deg_to_rad}" effort="300" velocity="7" />
+      <limit lower="0" upper="2.618" effort="300" velocity="7" />
       <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
     </joint>
 
@@ -199,7 +201,7 @@
       <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="${-75.00000 * deg_to_rad}" upper="${45.00000 * deg_to_rad}" effort="160" velocity="5.8"/>
+      <limit lower="-1.309" upper="0.768" effort="160" velocity="5.8" />
       <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
     </joint>
 
@@ -236,7 +238,7 @@
       <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="${-30.00000 * deg_to_rad}" upper="${30.00000 * deg_to_rad}" effort="100" velocity="4.8"/>
+      <limit lower="-0.524" upper="0.524" effort="100" velocity="4.8" />
       <dynamics friction="${leg_friction}" damping="${leg_damping}"/>
     </joint>