Commit b59d3724 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

added feet_ir sensors again (which were deleted at some point)

parent a2d38a99
......@@ -12,6 +12,7 @@ bioloid:
exp_adc5_frame: LAT_IR_right_link
exp_adc4_frame: IRLONG_link
adc3_frame: gyro_y
adc4_frame: gyro_x
exp_board_id: 192
......
......@@ -7,6 +7,12 @@
<xacro:include filename="$(find bioloid_description)/urdf/pan_tilt.xacro" />
<xacro:include filename="$(find bioloid_description)/urdf/sensors/ids_xs.xacro" />
<xacro:arg name="use_pan_tilt" default="false"/>
<!--feet sensor-->
<xacro:feet_ir left_parent="left_leg_ankle_roll" right_parent="right_leg_ankle_roll" update_rate="20" range="0.01"/>
<!--Two front sensors-->
<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.04 0.00 0.035" rpy="0 -1.745 0" />
......@@ -14,22 +20,31 @@
<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.396 0" />
</xacro:sharp_ir>
<!-- One long distance sensor-->
<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-->
<!-- <xacro:sharp_ir name="LAT_IR_left" parent="base_link" update_rate="20" fov="0.05" min_range="0.1" max_range="0.8">
<!-- Two 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.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.04 0.03 0.035" rpy="-1.5707 3.1416 0" />
</xacro:sharp_ir> -->
<xacro:feet_ir left_parent="left_leg_ankle_roll" right_parent="right_leg_ankle_roll" update_rate="20" range="0.01"/>
</xacro:sharp_ir>
<!-- this is for the back sensors
<xacro:sharp_ir name="BACK_IR_left" 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.5707 0" />
</xacro:sharp_ir>
<xacro:sharp_ir name="BACK_IR_right" 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.5707 0" />
</xacro:sharp_ir>
<xacro:feet_ir left_parent="left_leg_ankle_roll" right_parent="right_leg_ankle_roll" update_rate="20" range="0.01"/>
-->
<link name="battery_pack">
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment