diff --git a/bioloid_description/urdf/dexter.xacro b/bioloid_description/urdf/dexter.xacro index 8f30778d5c0b919c9772bd26d7c7ac05023df720..525f0c8d09cd05153e150219b6cb7ddcce1aa810 100755 --- a/bioloid_description/urdf/dexter.xacro +++ b/bioloid_description/urdf/dexter.xacro @@ -7,24 +7,23 @@ <xacro:sharp_ir name="IR1" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8"> - <origin xyz="0 0.0 0.035" rpy="-1.5707 -1.5707 0" /> + <origin xyz="-0.04 0.00 0.035" rpy="0 -1.8326 0" /> </xacro:sharp_ir> - - <xacro:sharp_ir name="IRL1" parent="base_link" update_rate="20" fov="0.05" min_range="0.20" max_range="1.5"> - <origin xyz="0 -0.05 0.035" rpy="-1.5707 -1.5707 0" /> + <xacro:sharp_ir name="IR2" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8"> + <origin xyz="0.04 0.00 0.035" rpy="0 -1.3090 0" /> </xacro:sharp_ir> -<!-- <xacro:sharp_ir name="IR2" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8"> - <origin xyz="0 -0.05 0.035" rpy="-1.5707 -1.5707 0" /> - </xacro:sharp_ir> --> + <xacro:sharp_ir name="IRLONG" parent="base_link" update_rate="20" fov="0.05" min_range="0.20" max_range="1.5"> + <origin xyz="0.00 -0.05 0.035" rpy="-1.5707 -1.5707 0" /> + </xacro:sharp_ir> - <!-- this is for the lateral sensors 3d component puts sensor vertical--> + <!-- this is for the lateral sensors--> <xacro:sharp_ir name="LAT_IR_left" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8"> - <origin xyz="0.05 0.04 0.035" rpy="-1.5707 0 0" /> + <origin xyz="0.04 0.03 0.035" rpy="-1.5707 0 0" /> </xacro:sharp_ir> <xacro:sharp_ir name="LAT_IR_right" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8"> - <origin xyz="-0.03 0.04 0.035" rpy="-1.5707 3.1416 0" /> + <origin xyz="-0.04 0.03 0.035" rpy="-1.5707 3.1416 0" /> </xacro:sharp_ir>