diff --git a/darwin_description/meshes/left_sensor_foot.stl b/darwin_description/meshes/left_sensor_foot.stl
new file mode 100755
index 0000000000000000000000000000000000000000..4a66c1fdfdf9b25c1692d333c8e009bfc85287bc
Binary files /dev/null and b/darwin_description/meshes/left_sensor_foot.stl differ
diff --git a/darwin_description/meshes/right_sensor_foot.stl b/darwin_description/meshes/right_sensor_foot.stl
new file mode 100755
index 0000000000000000000000000000000000000000..066ac5c00776d6d4a0e687c2137ab50c5caec843
Binary files /dev/null and b/darwin_description/meshes/right_sensor_foot.stl differ
diff --git a/darwin_description/urdf/darwin.gazebo b/darwin_description/urdf/darwin.gazebo
index a21cb8a7bf9ee79ab53a2f9739ec114c575cba91..d714feeee582f2a9c9154f7e2dad1cd11af34ff8 100644
--- a/darwin_description/urdf/darwin.gazebo
+++ b/darwin_description/urdf/darwin.gazebo
@@ -52,10 +52,6 @@
     <material>Gazebo/Grey</material>
   </gazebo>
 
-  <gazebo reference="left_leg_ankle_roll">
-    <material>Gazebo/Grey</material>
-  </gazebo>
-
   <gazebo reference="right_leg_pelvis_yaw">
     <material>Gazebo/Grey</material>
   </gazebo>
@@ -76,10 +72,6 @@
     <material>Gazebo/Grey</material>
   </gazebo>
 
-  <gazebo reference="right_leg_ankle_roll">
-    <material>Gazebo/Grey</material>
-  </gazebo>
-
   <gazebo reference="base_link">
     <gravity>false</gravity>
     <selfCollide>false</selfCollide>
@@ -236,19 +228,6 @@
     <kd>0.0</kd>
   </gazebo>
 
-  <gazebo reference="left_leg_ankle_roll">
-    <gravity>false</gravity>
-    <selfCollide>false</selfCollide>
-    <maxContacts>10</maxContacts>
-    <dampingFactor>0.2</dampingFactor>
-    <maxVel>0.0</maxVel>
-    <minDepth>0.0</minDepth>
-    <mu1>1.000000</mu1>
-    <mu2>1.000000</mu2>
-    <kp>0.0</kp>
-    <kd>0.0</kd>
-  </gazebo>
-
   <gazebo reference="right_leg_pelvis_pitch">
     <gravity>false</gravity>
     <selfCollide>false</selfCollide>
@@ -314,19 +293,6 @@
     <kd>0.0</kd>
   </gazebo>
 
-  <gazebo reference="right_leg_ankle_roll">
-    <gravity>false</gravity>
-    <selfCollide>false</selfCollide>
-    <maxContacts>10</maxContacts>
-    <dampingFactor>0.2</dampingFactor>
-    <maxVel>0.0</maxVel>
-    <minDepth>0.0</minDepth>
-    <mu1>1.00000</mu1>
-    <mu2>1.00000</mu2>
-    <kp>0.0</kp>
-    <kd>0.0</kd>
-  </gazebo>
-
   <gazebo reference="j_tilt">
     <implicitSpringDamper>true</implicitSpringDamper>
     <stopCfm>0.0</stopCfm>
@@ -392,12 +358,6 @@
     <stopErp>0.0</stopErp>
   </gazebo>
 
-  <gazebo reference="j_ankle_roll_l">
-    <implicitSpringDamper>true</implicitSpringDamper>
-    <stopCfm>0.0</stopCfm>
-    <stopErp>0.0</stopErp>
-  </gazebo>
-
   <gazebo reference="j_hip_yaw_r">
     <implicitSpringDamper>true</implicitSpringDamper>
     <stopCfm>0.0</stopCfm>
@@ -428,12 +388,6 @@
     <stopErp>0.0</stopErp>
   </gazebo>
 
-  <gazebo reference="j_ankle_roll_r">
-    <implicitSpringDamper>true</implicitSpringDamper>
-    <stopCfm>0.0</stopCfm>
-    <stopErp>0.0</stopErp>
-  </gazebo>
-
   <gazebo>
     <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
       <robotNamespace>/darwin</robotNamespace>
diff --git a/darwin_description/urdf/darwin.xacro b/darwin_description/urdf/darwin.xacro
index 4d82da533eb16ccbd8a7b90a74c89771453830c2..00dcca5b048cb52808696c1f814e2bc361971535 100755
--- a/darwin_description/urdf/darwin.xacro
+++ b/darwin_description/urdf/darwin.xacro
@@ -6,6 +6,8 @@
   <xacro:include filename="$(find darwin_description)/urdf/sensors/bno055.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/left_hand.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/right_hand.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_foot.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_foot.xacro" />
 
   <xacro:left_hand parent="left_arm_high">
     <origin xyz="0.0 -0.060 0.016" rpy="-1.5707 0 0" />
@@ -15,6 +17,14 @@
     <origin xyz="0.0 -0.06 0.016" rpy="-1.5707 0 0" />
   </xacro:right_hand>
 
+  <xacro:left_foot parent="left_leg_ankle_pitch">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:left_foot>
+
+  <xacro:right_foot parent="right_leg_ankle_pitch">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:right_foot>
+
   <xacro:ids_xs name="darwin_cam" parent="head">
     <origin xyz="0.0 0.005 0.045" rpy="0 -2.2777 1.5707" />
   </xacro:ids_xs>
diff --git a/darwin_description/urdf/darwin_ceabot.xacro b/darwin_description/urdf/darwin_ceabot.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..dfc0a763913d404e5feaffc6f7cd3a4d4210718d
--- /dev/null
+++ b/darwin_description/urdf/darwin_ceabot.xacro
@@ -0,0 +1,36 @@
+<robot name="darwin" xmlns:xacro="http://www.ros.org/wiki/xacro">
+ 
+  <xacro:include filename="$(find darwin_description)/urdf/darwin_low_res.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/sensors/darwin_imu.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/sensors/ids_xs.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/sensors/bno055.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_hand.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_hand.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_sensor_foot.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_sensor_foot.xacro" />
+
+  <xacro:left_hand parent="left_arm_high">
+    <origin xyz="0.0 -0.060 0.016" rpy="-1.5707 0 0" />
+  </xacro:left_hand>
+
+  <xacro:right_hand parent="right_arm_high">
+    <origin xyz="0.0 -0.06 0.016" rpy="-1.5707 0 0" />
+  </xacro:right_hand>
+
+  <xacro:left_sensor_foot parent="left_leg_ankle_pitch" update_rate="10" range="0.01">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:left_sensor_foot>
+
+  <xacro:right_sensor_foot parent="right_leg_ankle_pitch" update_rate="10" range="0.01">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:right_sensor_foot>
+
+  <xacro:ids_xs name="darwin_cam" parent="head">
+    <origin xyz="0.0 0.005 0.045" rpy="0 -2.2777 1.5707" />
+  </xacro:ids_xs>
+
+  <xacro:bno055 name="darwin_imu" parent="base_link">
+    <origin xyz="0.0 0.0 -0.05" rpy="0 0 1.5707" />
+  </xacro:bno055>
+
+</robot>
diff --git a/darwin_description/urdf/darwin_grippers.xacro b/darwin_description/urdf/darwin_grippers.xacro
index 43829c782d58039452bde7ef6ac6b5c707a6952e..a0ee89dbef92184f84b98b3e3505502b90fba3fc 100755
--- a/darwin_description/urdf/darwin_grippers.xacro
+++ b/darwin_description/urdf/darwin_grippers.xacro
@@ -1,815 +1,20 @@
 <robot name="darwin" xmlns:xacro="http://www.ros.org/wiki/xacro">
  
-  <xacro:include filename="$(find darwin_description)/urdf/darwin.gazebo" />
+  <xacro:include filename="$(find darwin_description)/urdf/darwin_low_res.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/sensors/darwin_imu.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/sensors/ids_xs.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/sensors/bno055.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/gripper.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_foot.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_foot.xacro" />
 
-  <link name="base_link">
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/body.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.975599" />
-      <origin xyz="0.00002469 -0.029448 -0.01576428" rpy="0 0 0"/>
-      <inertia ixx="0.00175853" ixy="-0.00000031" ixz="0.00000081" iyy="0.00187076" iyz="-0.00002473" izz="0.00246393" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/body_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="neck">
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/neck.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0243577" />
-      <origin xyz="-2.4722012e-006 -0.021006105 -0.0010218021" rpy="0 0 0"/>
-      <inertia ixx="3.4606288e-006" ixy="-1.810192e-010" ixz="-6.1530042e-011" iyy="9.0467035e-006" iyz="1.5988071e-007" izz="1.0024371e-005" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/neck_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="head">
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/head.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.158042" />
-      <origin xyz="1.4076285e-005 0.019086672 0.004621368" rpy="0 0 0"/>
-      <inertia ixx="0.00015147251" ixy="-1.8688115e-007" ixz="5.4521838e-009" iyy="0.00014149723" iyz="-1.3452525e-005" izz="0.00015599345" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/head_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_shoulder">
-    <visual>
-      <origin xyz="0.022 -0.016 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_shoulder.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.025913" />
-      <origin xyz="-0.01643844 0.01337172 0.0000000" rpy="0 0 0"/>
-      <inertia ixx="0.00001012" ixy="-0.00000071" ixz="0.00000000" iyy="0.0000099" iyz="0.00000000" izz="0.00000384" />
-    </inertial>
-    <collision>
-      <origin xyz="0.022 -0.016 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_shoulder_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_arm_high" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_arm_high.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.168377" />
-      <origin xyz="-0.0000229 -0.03563612 0.00239371" rpy="0 0 0"/>
-      <inertia ixx="0.00014389" ixy="0.00000009" ixz="0.00000031" iyy="0.00004108" iyz="-0.00000970" izz="0.00013383" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_arm_high_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <xacro:gripper name="l" parent="left_arm_high">
-    <origin xyz="0.0 -0.060 0.016" rpy="-1.5707 0 0" />
-  </xacro:gripper>
-
-  <link name="right_shoulder" >
-    <visual>
-      <origin xyz="-0.022 -0.016 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_shoulder.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.025913" />
-      <origin xyz="0.01643844 0.01337172 0.00000000" rpy="0 0 0"/>
-      <inertia ixx="0.00001012" ixy="0.00000071" ixz="0.00000000" iyy="0.00000990" iyz="0.00000000" izz="0.00000384" />
-    </inertial>
-    <collision>
-      <origin xyz="-0.022 -0.016 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_shoulder_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_arm_high" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_arm_high.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.168377" />
-      <origin xyz="0.00002296 -0.03563612 0.00239371" rpy="0 0 0"/>
-      <inertia ixx="0.00014389" ixy="-0.00000009" ixz="-0.00000031" iyy="0.00004108" iyz="-0.00000970" izz="0.00013383" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_arm_high_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <xacro:gripper name="r" parent="right_arm_high">
-    <origin xyz="0.0 -0.06 0.016" rpy="-1.5707 0 0" />
-  </xacro:gripper>
-
-  <link name="left_leg_pelvis_yaw" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_pelvis_yaw.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.027069" />
-      <origin xyz="0.00000000 0.0227787 0.00288919" rpy="0 0 0"/>
-      <inertia ixx="0.00001303" ixy="0.00000000" ixz="0.00000000" iyy="0.00001210" iyz="0.00000003" izz="0.00000422" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_pelvis_yaw_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_leg_pelvis_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_pelvis_roll.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.16710" />
-      <origin xyz="0.00007233 -0.01111330 -0.02044569" rpy="0 0 0"/>
-      <inertia ixx="0.00012130" ixy="0.0" ixz="0.0" iyy="0.00010824" iyz="0.0" izz="0.00004476" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_pelvis_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_leg_pelvis_pitch" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_pelvis_pitch.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.119043" />
-      <origin xyz="0.00001568 -0.07105466 0.00142329" rpy="0 0 0"/>
-      <inertia ixx="0.00008127" ixy="0.0" ixz="0.0" iyy="0.00003624" iyz="0.0" izz="0.00009704" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_pelvis_pitch_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_leg_knee" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_knee.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0703098" />
-      <origin xyz="0.00006376 -0.03683715 0.00894668" rpy="0 0 0"/>
-      <inertia ixx="0.0000824" ixy="0.0" ixz="0.0" iyy="0.00005574" iyz="0.0" izz="0.00010187" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_knee_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_leg_ankle_pitch" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_ankle_pitch.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.167108" />
-      <origin xyz="-0.00002505 0.01111330 -0.02044569" rpy="0 0 0"/>
-      <inertia ixx="0.00012130" ixy="0.0" ixz="0.0" iyy="0.00010823" iyz="0.0" izz="0.00004475" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_pitch_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="left_leg_ankle_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_ankle_roll.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0794462" />
-      <origin xyz="0.01094328 -0.02730949 -0.00102239" rpy="0 0 0"/>
-      <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.00010548" iyz="0.0" izz="0.00003613" />
-    </inertial>
-    <collision>
-      <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_leg_pelvis_yaw" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_pelvis_yaw.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.027069" />
-      <origin xyz="0.00000000 0.02277874 0.00013919" rpy="0 0 0"/>
-      <inertia ixx="0.00001303" ixy="0.0" ixz="0.0" iyy="0.00001210" iyz="0.0" izz="0.00000422" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_pelvis_yaw_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_leg_pelvis_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_pelvis_roll.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.167108" />
-      <origin xyz="-0.00007115 -0.0111133 -0.02044569" rpy="0 0 0"/>
-      <inertia ixx="0.00012130" ixy="0.0" ixz="0.0" iyy="0.00010823" iyz="0.0" izz="0.00004475" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_pelvis_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_leg_pelvis_pitch" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_pelvis_pitch.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.119043" />
-      <origin xyz="-0.00005071 -0.07105466 0.00142329" rpy="0 0 0"/>
-      <inertia ixx="0.00008127" ixy="0.0" ixz="0.0" iyy="0.00003624" iyz="0.0" izz="0.00009704" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_pelvis_pitch_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_leg_knee" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_knee.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0703098" />
-      <origin xyz="-0.00006415 -0.03683715 0.00894668" rpy="0 0 0"/>
-      <inertia ixx="0.00008246" ixy="0.0" ixz="0.0" iyy="0.00005574" iyz="0.0" izz="0.00010187" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_knee_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_leg_ankle_pitch" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_ankle_pitch.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.167108" />
-      <origin xyz="-0.00007115 0.01111330 -0.02044569" rpy="0 0 0"/>
-      <inertia ixx="0.00012130" ixy="0.0" ixz="0.0" iyy="0.00010823" iyz="0.0" izz="0.00004475" />
-    </inertial>
-    <collision>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_pitch_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <link name="right_leg_ankle_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_ankle_roll.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0794462" />
-      <origin xyz="-0.01094329 -0.02730949 -0.00102239" rpy="0 0 0"/>
-      <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.0001054" iyz="0.0" izz="0.00003613" />
-    </inertial>
-    <collision>
-      <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
-  <joint name="j_pan" type="revolute">
-    <parent link="base_link"/>
-    <child link="neck"/>
-    <origin xyz="0.0 0.051 0.0" rpy="0 0 0" />
-    <axis xyz="0 1 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_pan">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_pan">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="pan_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_tilt" type="revolute">
-    <parent link="neck"/>
-    <child link="head"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="-1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_tilt">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_tilt">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="tilt_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_shoulder_pitch_l" type="revolute">
-    <parent link="base_link"/>
-    <child link="left_shoulder"/>
-    <origin xyz="0.06 0 0" rpy="0 0 0" />
-    <axis xyz="1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_shoulder_pitch_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_shoulder_pitch_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="shoulder_pitch_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_shoulder_roll_l" type="revolute">
-    <parent link="left_shoulder"/>
-    <child link="left_arm_high"/>
-    <origin xyz="0.022 -0.016 0.0" rpy="0 0 0.785398163" />
-    <axis xyz="0 0 -1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_shoulder_roll_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_shoulder_roll_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="shoulder_roll_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_shoulder_pitch_r" type="revolute">
-    <parent link="base_link"/>
-    <child link="right_shoulder"/>
-    <origin xyz="-0.06 0 0" rpy="0 0 0" />
-    <axis xyz="-1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_shoulder_pitch_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_shoulder_pitch_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="shoulder_pitch_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_shoulder_roll_r" type="revolute">
-    <parent link="right_shoulder"/>
-    <child link="right_arm_high"/>
-    <origin xyz="-0.022 -0.016 0" rpy="0 0 -0.785398163" />
-    <axis xyz="0 0 -1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_shoulder_roll_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_shoulder_roll_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="shoulder_roll_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_hip_yaw_l" type="revolute">
-    <parent link="base_link"/>
-    <child link="left_leg_pelvis_yaw"/>
-    <origin xyz="0.037 -0.1222 -0.005" rpy="0 0 0" />
-    <axis xyz="0 -1 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_hip_yaw_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_hip_yaw_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="hip_yaw_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_hip_roll_l" type="revolute">
-    <parent link="left_leg_pelvis_yaw"/>
-    <child link="left_leg_pelvis_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 -1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_hip_roll_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_hip_roll_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="hip_roll_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_hip_pitch_l" type="revolute">
-    <parent link="left_leg_pelvis_roll"/>
-    <child link="left_leg_pelvis_pitch"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="-1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_hip_pitch_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_hip_pitch_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="hip_pitch_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_knee_l" type="revolute">
-    <parent link="left_leg_pelvis_pitch"/>
-    <child link="left_leg_knee"/>
-    <origin xyz="0 -0.093 0" rpy="0 0 0" />
-    <axis xyz="-1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_knee_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_knee_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="knee_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_ankle_pitch_l" type="revolute">
-    <parent link="left_leg_knee"/>
-    <child link="left_leg_ankle_pitch"/>
-    <origin xyz="0 -0.093 0" rpy="0 0 0" />
-    <axis xyz="1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_pitch_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_pitch_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_pitch_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_ankle_roll_l" type="revolute">
-    <parent link="left_leg_ankle_pitch"/>
-    <child link="left_leg_ankle_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_roll_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_roll_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_roll_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_hip_yaw_r" type="revolute">
-    <parent link="base_link"/>
-    <child link="right_leg_pelvis_yaw"/>
-    <origin xyz="-0.037 -0.1222 -0.005" rpy="0 0 0" />
-    <axis xyz="0 -1 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_hip_yaw_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_hip_yaw_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="hip_yaw_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_hip_roll_r" type="revolute">
-    <parent link="right_leg_pelvis_yaw"/>
-    <child link="right_leg_pelvis_roll"/>
+  <xacro:left_foot parent="left_leg_ankle_pitch">
     <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 -1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
+  </xacro:right_hand>
 
-  <transmission name="tran_hip_roll_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_hip_roll_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="hip_roll_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_hip_pitch_r" type="revolute">
-    <parent link="right_leg_pelvis_roll"/>
-    <child link="right_leg_pelvis_pitch"/>
+  <xacro:right_foot parent="right_leg_ankle_pitch">
     <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_hip_pitch_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_hip_pitch_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="hip_pitch_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_knee_r" type="revolute">
-    <parent link="right_leg_pelvis_pitch"/>
-    <child link="right_leg_knee"/>
-    <origin xyz="0.0 -0.093 0" rpy="0 0 0" />
-    <axis xyz="1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_knee_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_knee_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="knee_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_ankle_pitch_r" type="revolute">
-    <parent link="right_leg_knee"/>
-    <child link="right_leg_ankle_pitch"/>
-    <origin xyz="0.0 -0.093 0" rpy="0 0 0" />
-    <axis xyz="-1 0 0" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_pitch_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_pitch_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_pitch_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
-  <joint name="j_ankle_roll_r" type="revolute">
-    <parent link="right_leg_ankle_pitch"/>
-    <child link="right_leg_ankle_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_roll_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_roll_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_roll_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
+  </xacro:right_hand>
 
   <xacro:ids_xs name="darwin_cam" parent="head">
     <origin xyz="0.0 0.005 0.045" rpy="0 -2.2777 1.5707" />
diff --git a/darwin_description/urdf/darwin_high_res.xacro b/darwin_description/urdf/darwin_high_res.xacro
index 59f810d57e62d8de03656357c99634acdab27d62..b953a1387579453df7e82bbe1f3c4678f2d4a7fb 100755
--- a/darwin_description/urdf/darwin_high_res.xacro
+++ b/darwin_description/urdf/darwin_high_res.xacro
@@ -291,29 +291,6 @@
     </collision>
   </link>
 
-  <link name="left_leg_ankle_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/left_leg_ankle_roll.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0794462" />
-      <origin xyz="0.01094328 -0.02730949 -0.00102239" rpy="0 0 0"/>
-      <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.00010548" iyz="0.0" izz="0.00003613" />
-    </inertial>
-    <collision>
-      <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
   <link name="right_leg_pelvis_yaw" >
     <visual>
       <origin xyz="0 0 0" rpy="0 0 0" />
@@ -429,29 +406,6 @@
     </collision>
   </link>
 
-  <link name="right_leg_ankle_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/right_leg_ankle_roll.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0794462" />
-      <origin xyz="-0.01094329 -0.02730949 -0.00102239" rpy="0 0 0"/>
-      <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.0001054" iyz="0.0" izz="0.00003613" />
-    </inertial>
-    <collision>
-      <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
   <joint name="j_pan" type="revolute">
     <parent link="base_link"/>
     <child link="neck"/>
@@ -672,26 +626,6 @@
     </actuator>
   </transmission>
 
-  <joint name="j_ankle_roll_l" type="revolute">
-    <parent link="left_leg_ankle_pitch"/>
-    <child link="left_leg_ankle_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_roll_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_roll_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_roll_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
   <joint name="j_hip_yaw_r" type="revolute">
     <parent link="base_link"/>
     <child link="right_leg_pelvis_yaw"/>
@@ -792,26 +726,6 @@
     </actuator>
   </transmission>
 
-  <joint name="j_ankle_roll_r" type="revolute">
-    <parent link="right_leg_ankle_pitch"/>
-    <child link="right_leg_ankle_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_roll_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_roll_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_roll_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
   <xacro:ids_xs name="darwin_cam" parent="head">
     <origin xyz="0.0 0.005 0.045" rpy="0 -2.2777 1.5707" />
   </xacro:ids_xs>
diff --git a/darwin_description/urdf/darwin_low_res.xacro b/darwin_description/urdf/darwin_low_res.xacro
index 4770c14aeccca819180d44c2c29bffcd76952751..cd2dd5e05587847ba54b005cf6355caaafd71f5e 100755
--- a/darwin_description/urdf/darwin_low_res.xacro
+++ b/darwin_description/urdf/darwin_low_res.xacro
@@ -278,29 +278,6 @@
     </collision>
   </link>
 
-  <link name="left_leg_ankle_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0794462" />
-      <origin xyz="0.01094328 -0.02730949 -0.00102239" rpy="0 0 0"/>
-      <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.00010548" iyz="0.0" izz="0.00003613" />
-    </inertial>
-    <collision>
-      <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
   <link name="right_leg_pelvis_yaw" >
     <visual>
       <origin xyz="0 0 0" rpy="0 0 0" />
@@ -416,29 +393,6 @@
     </collision>
   </link>
 
-  <link name="right_leg_ankle_roll" >
-    <visual>
-      <origin xyz="0 0 0" rpy="0 0 0" />
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
-      </geometry>
-      <material name="Grey">
-        <color rgba="0.79 0.82 0.93 1.0"/>
-      </material>
-    </visual>
-    <inertial>
-      <mass value="0.0794462" />
-      <origin xyz="-0.01094329 -0.02730949 -0.00102239" rpy="0 0 0"/>
-      <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.0001054" iyz="0.0" izz="0.00003613" />
-    </inertial>
-    <collision>
-      <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
-      <geometry>
-        <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
-      </geometry>
-    </collision>
-  </link>
-
   <joint name="j_pan" type="revolute">
     <parent link="base_link"/>
     <child link="neck"/>
@@ -659,26 +613,6 @@
     </actuator>
   </transmission>
 
-  <joint name="j_ankle_roll_l" type="revolute">
-    <parent link="left_leg_ankle_pitch"/>
-    <child link="left_leg_ankle_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_roll_l">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_roll_l">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_roll_l_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
   <joint name="j_hip_yaw_r" type="revolute">
     <parent link="base_link"/>
     <child link="right_leg_pelvis_yaw"/>
@@ -779,24 +713,4 @@
     </actuator>
   </transmission>
 
-  <joint name="j_ankle_roll_r" type="revolute">
-    <parent link="right_leg_ankle_pitch"/>
-    <child link="right_leg_ankle_roll"/>
-    <origin xyz="0 0 0" rpy="0 0 0" />
-    <axis xyz="0 0 1" />
-    <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
-    <dynamics damping="0.4"/>
-  </joint>
-
-  <transmission name="tran_ankle_roll_r">
-    <type>transmission_interface/SimpleTransmission</type>
-    <joint name="j_ankle_roll_r">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-    </joint>
-    <actuator name="ankle_roll_r_motor">
-      <hardwareInterface>EffortJointInterface</hardwareInterface>
-      <mechanicalReduction>1</mechanicalReduction>
-    </actuator>
-  </transmission>
-
 </robot>
diff --git a/darwin_description/urdf/darwin_sc.xacro b/darwin_description/urdf/darwin_sc.xacro
index a8d5efaf02b8412afdd7da58a9ebb051ab0815b5..7009102662021f8042845856ac5f7bb0c1384ee5 100755
--- a/darwin_description/urdf/darwin_sc.xacro
+++ b/darwin_description/urdf/darwin_sc.xacro
@@ -5,6 +5,16 @@
   <xacro:include filename="$(find darwin_description)/urdf/sensors/ids_xs.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/sensors/bno055.xacro" />
   <xacro:include filename="$(find darwin_description)/urdf/gripper_sc_low_res.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_foot.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_foot.xacro" />
+
+  <xacro:left_foot parent="left_leg_ankle_pitch">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:left_foot>
+
+  <xacro:right_foot parent="right_leg_ankle_pitch">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:right_foot>
 
   <xacro:gripper_sc name="l" parent="left_arm_high">
     <origin xyz="0.0 -0.060 0.016" rpy="-1.5707 0 0" />
diff --git a/darwin_description/urdf/left_foot.gazebo b/darwin_description/urdf/left_foot.gazebo
new file mode 100644
index 0000000000000000000000000000000000000000..dc76eb4086c32748612f736571bb2f7ceabfe212
--- /dev/null
+++ b/darwin_description/urdf/left_foot.gazebo
@@ -0,0 +1,26 @@
+<?xml version="1.0"?>
+<robot>
+  <gazebo reference="left_leg_ankle_roll">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="left_leg_ankle_roll">
+    <gravity>false</gravity>
+    <selfCollide>false</selfCollide>
+    <maxContacts>10</maxContacts>
+    <dampingFactor>0.2</dampingFactor>
+    <maxVel>0.0</maxVel>
+    <minDepth>0.0</minDepth>
+    <mu1>1.000000</mu1>
+    <mu2>1.000000</mu2>
+    <kp>0.0</kp>
+    <kd>0.0</kd>
+  </gazebo>
+
+  <gazebo reference="j_ankle_roll_l">
+    <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
+  </gazebo>
+
+</robot>
diff --git a/darwin_description/urdf/left_foot.xacro b/darwin_description/urdf/left_foot.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..3f5b6247c59b71c2d67f3b860106aa29f8979b1c
--- /dev/null
+++ b/darwin_description/urdf/left_foot.xacro
@@ -0,0 +1,52 @@
+<?xml version="1.0"?>
+
+<root xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find darwin_description)/urdf/left_foot.gazebo" />
+
+  <xacro:macro name="left_foot" params="parent *origin">
+    <link name="left_leg_ankle_roll" >
+      <visual>
+        <origin xyz="0 0 0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
+        </geometry>
+        <material name="Grey">
+          <color rgba="0.79 0.82 0.93 1.0"/>
+        </material>
+      </visual>
+      <inertial>
+        <mass value="0.0794462" />
+        <origin xyz="0.01094328 -0.02730949 -0.00102239" rpy="0 0 0"/>
+        <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.00010548" iyz="0.0" izz="0.00003613" />
+      </inertial>
+      <collision>
+        <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/bounding_boxes/left_leg_ankle_roll_bb.stl" />
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="j_ankle_roll_l" type="revolute">
+      <parent link="${parent}"/>
+      <child link="left_leg_ankle_roll"/>
+      <xacro:insert_block name="origin" />
+      <axis xyz="0 0 1" />
+      <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
+      <dynamics damping="0.4"/>
+    </joint>
+
+    <transmission name="tran_ankle_roll_l">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="j_ankle_roll_l">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+      </joint>
+      <actuator name="ankle_roll_l_motor">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+  </xacro:macro>
+
+</root>
diff --git a/darwin_description/urdf/left_sensor_foot.xacro b/darwin_description/urdf/left_sensor_foot.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..d9ad32f839b29e0c809643bf87b2f926154083a3
--- /dev/null
+++ b/darwin_description/urdf/left_sensor_foot.xacro
@@ -0,0 +1,86 @@
+<?xml version="1.0"?>
+
+<root xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find darwin_description)/urdf/left_foot.gazebo" />
+  <xacro:include filename="$(find bioloid_description)/urdf/sensors/cny70_ir.xacro" />
+
+  <xacro:macro name="left_sensor_foot" params="parent *origin update_rate range">
+    <link name="left_leg_ankle_roll" >
+      <visual>
+        <origin xyz="0 0 0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/left_sensor_foot.stl" />
+        </geometry>
+        <material name="Grey">
+          <color rgba="0.79 0.82 0.93 1.0"/>
+        </material>
+      </visual>
+      <inertial>
+        <mass value="0.07944623" />
+        <origin xyz="0.00787555 -0.03128293 -0.00010476" rpy="0 0 0"/>
+        <inertia ixx="0.00006020" ixy="-0.00000148" ixz="-0.0000010" iyy="0.00008141" iyz="0.00000086" izz="0.00002745" />
+      </inertial>
+      <collision>
+        <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/left_sensor_foot.stl" />
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="j_ankle_roll_l" type="revolute">
+      <parent link="${parent}"/>
+      <child link="left_leg_ankle_roll"/>
+      <xacro:insert_block name="origin" />
+      <axis xyz="0 0 1" />
+      <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
+      <dynamics damping="0.4"/>
+    </joint>
+
+    <transmission name="tran_ankle_roll_l">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="j_ankle_roll_l">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+      </joint>
+      <actuator name="ankle_roll_l_motor">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+
+    <xacro:cny70_ir name="left_down_right_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.0185 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_down_right_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.0185 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_down_right_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.011 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_down_left_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.0335 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_down_left_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.0335 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_down_left_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.026 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_front_right" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.0186 -0.0285 0.051" rpy="0 -1.5707 0" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="left_front_left" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.0336 -0.0285 0.051" rpy="-1.5707 -1.5707 0" />
+    </xacro:cny70_ir>
+
+  </xacro:macro>
+
+</root>
diff --git a/darwin_description/urdf/right_foot.gazebo b/darwin_description/urdf/right_foot.gazebo
new file mode 100644
index 0000000000000000000000000000000000000000..8b477296013d3ed2ac4a9ee94f73f14e8c0fc5e3
--- /dev/null
+++ b/darwin_description/urdf/right_foot.gazebo
@@ -0,0 +1,26 @@
+<?xml version="1.0"?>
+<robot>
+  <gazebo reference="right_leg_ankle_roll">
+    <material>Gazebo/Grey</material>
+  </gazebo>
+
+  <gazebo reference="right_leg_ankle_roll">
+    <gravity>false</gravity>
+    <selfCollide>false</selfCollide>
+    <maxContacts>10</maxContacts>
+    <dampingFactor>0.2</dampingFactor>
+    <maxVel>0.0</maxVel>
+    <minDepth>0.0</minDepth>
+    <mu1>1.00000</mu1>
+    <mu2>1.00000</mu2>
+    <kp>0.0</kp>
+    <kd>0.0</kd>
+  </gazebo>
+
+  <gazebo reference="j_ankle_roll_r">
+    <implicitSpringDamper>true</implicitSpringDamper>
+    <stopCfm>0.0</stopCfm>
+    <stopErp>0.0</stopErp>
+  </gazebo>
+
+</robot>
diff --git a/darwin_description/urdf/right_foot.xacro b/darwin_description/urdf/right_foot.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..977843f2c398df4fc700b371de9b24a8c54940f5
--- /dev/null
+++ b/darwin_description/urdf/right_foot.xacro
@@ -0,0 +1,52 @@
+<?xml version="1.0"?>
+
+<root xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find darwin_description)/urdf/right_foot.gazebo" />
+
+  <xacro:macro name="right_foot" params="parent *origin">
+    <link name="right_leg_ankle_roll" >
+      <visual>
+        <origin xyz="0 0 0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
+        </geometry>
+        <material name="Grey">
+          <color rgba="0.79 0.82 0.93 1.0"/>
+        </material>
+      </visual>
+      <inertial>
+        <mass value="0.0794462" />
+        <origin xyz="-0.01094329 -0.02730949 -0.00102239" rpy="0 0 0"/>
+        <inertia ixx="0.00007597" ixy="0.0" ixz="0.0" iyy="0.0001054" iyz="0.0" izz="0.00003613" />
+      </inertial>
+      <collision>
+        <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/bounding_boxes/right_leg_ankle_roll_bb.stl" />
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="j_ankle_roll_r" type="revolute">
+      <parent link="${parent}"/>
+      <child link="right_leg_ankle_roll"/>
+      <xacro:insert_block name="origin" />
+      <axis xyz="0 0 1" />
+      <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
+      <dynamics damping="0.4"/>
+    </joint>
+
+    <transmission name="tran_ankle_roll_r">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="j_ankle_roll_r">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+      </joint>
+      <actuator name="ankle_roll_r_motor">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+  </xacro:macro>
+
+</root>
diff --git a/darwin_description/urdf/right_sensor_foot.xacro b/darwin_description/urdf/right_sensor_foot.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..f70603c22b292a661cc81c6385e5ae14f35346e9
--- /dev/null
+++ b/darwin_description/urdf/right_sensor_foot.xacro
@@ -0,0 +1,86 @@
+<?xml version="1.0"?>
+
+<root xmlns:xacro="http://ros.org/wiki/xacro">
+
+  <xacro:include filename="$(find darwin_description)/urdf/right_foot.gazebo" />
+  <xacro:include filename="$(find bioloid_description)/urdf/sensors/cny70_ir.xacro" />
+
+  <xacro:macro name="right_sensor_foot" params="parent *origin update_rate range">
+    <link name="right_leg_ankle_roll" >
+      <visual>
+        <origin xyz="0 0 0" rpy="0 0 0" />
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/right_sensor_foot.stl" />
+        </geometry>
+        <material name="Grey">
+          <color rgba="0.79 0.82 0.93 1.0"/>
+        </material>
+      </visual>
+      <inertial>
+        <mass value="0.07944623" />
+        <origin xyz="-0.00825113 -0.03128300 -0.00010280" rpy="0 0 0"/>
+        <inertia ixx="0.00006020" ixy="0.00000138" ixz="0.00000006" iyy="0.00008138" iyz="0.00000086" izz="0.00002742" />
+      </inertial>
+      <collision>
+        <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
+        <geometry>
+          <mesh filename="package://darwin_description/meshes/right_sensor_foot.stl" />
+        </geometry>
+      </collision>
+    </link>
+
+    <joint name="j_ankle_roll_r" type="revolute">
+      <parent link="${parent}"/>
+      <child link="right_leg_ankle_roll"/>
+      <xacro:insert_block name="origin" />
+      <axis xyz="0 0 1" />
+      <limit effort="2.5" velocity="6.0" lower="-3.14" upper="3.14" />
+      <dynamics damping="0.4"/>
+    </joint>
+
+    <transmission name="tran_ankle_roll_r">
+      <type>transmission_interface/SimpleTransmission</type>
+      <joint name="j_ankle_roll_r">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+      </joint>
+      <actuator name="ankle_roll_r_motor">
+        <hardwareInterface>EffortJointInterface</hardwareInterface>
+        <mechanicalReduction>1</mechanicalReduction>
+      </actuator>
+    </transmission>
+
+    <xacro:cny70_ir name="right_down_right_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.0335 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_down_right_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.0335 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_down_right_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.026 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_down_left_rear" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.0185 -0.0325 0.0065" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_down_left_middle" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.0185 -0.0325 0.0275" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_down_left_front" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.011 -0.0325 0.0485" rpy="1.5707 0 -1.5707" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_front_right" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="-0.0336 -0.0285 0.051" rpy="0 -1.5707 0" />
+    </xacro:cny70_ir>
+
+    <xacro:cny70_ir name="right_front_left" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
+      <origin xyz="0.0186 -0.0285 0.051" rpy="-1.5707 -1.5707 0" />
+    </xacro:cny70_ir>
+
+  </xacro:macro>
+
+</root>