Skip to content
Snippets Groups Projects
Commit e8240800 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Changed the parent link of the IR sensors of the feet.

parent 4fedadd3
No related branches found
No related tags found
1 merge request!8Kinetic migration
......@@ -49,35 +49,35 @@
</actuator>
</transmission>
<xacro:cny70_ir name="left_down_right_rear" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_right_rear" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_right_middle" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_right_front" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_left_rear" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_left_middle" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_down_left_front" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_front_right" namespace="darwin" parent="left_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="left_front_left" namespace="darwin" parent="left_leg_ankle_roll" 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>
......
......@@ -49,35 +49,35 @@
</actuator>
</transmission>
<xacro:cny70_ir name="right_down_right_rear" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_right_rear" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_right_middle" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_right_front" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_left_rear" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_left_middle" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_down_left_front" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_front_right" namespace="darwin" parent="right_leg_ankle_roll" 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" namespace="darwin" parent="${parent}" update_rate="${update_rate}" fov="0.05" min_range="0.001" max_range="${range}">
<xacro:cny70_ir name="right_front_left" namespace="darwin" parent="right_leg_ankle_roll" 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>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment