From e8240800e3e95c2399c74e69a6e554f83317f37c Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Thu, 31 Aug 2017 13:26:02 +0200 Subject: [PATCH] Changed the parent link of the IR sensors of the feet. --- darwin_description/urdf/left_sensor_foot.xacro | 16 ++++++++-------- darwin_description/urdf/right_sensor_foot.xacro | 16 ++++++++-------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/darwin_description/urdf/left_sensor_foot.xacro b/darwin_description/urdf/left_sensor_foot.xacro index 76829b7..5431946 100755 --- a/darwin_description/urdf/left_sensor_foot.xacro +++ b/darwin_description/urdf/left_sensor_foot.xacro @@ -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> diff --git a/darwin_description/urdf/right_sensor_foot.xacro b/darwin_description/urdf/right_sensor_foot.xacro index 971b571..f1e86c5 100755 --- a/darwin_description/urdf/right_sensor_foot.xacro +++ b/darwin_description/urdf/right_sensor_foot.xacro @@ -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> -- GitLab