Commit b55b8bc3 authored by Günter Niemeyer's avatar Günter Niemeyer
Browse files

Re-Calibrated the Camera Mount Angle to 17deg

This helps line up the depth points better.  Careful - the 17deg may be different on different bots.
parent f906c418
No related merge requests found
Showing with 4 additions and 22 deletions
+4 -22
...@@ -71,11 +71,11 @@ ...@@ -71,11 +71,11 @@
<!-- which is 0.04875 in front of the wheel axle. --> <!-- which is 0.04875 in front of the wheel axle. -->
<!-- So shifted 0.15058 in front of the wheel axle. --> <!-- So shifted 0.15058 in front of the wheel axle. -->
<!-- Also Shifted 0.03633 above the wheel axle. --> <!-- Also Shifted 0.03633 above the wheel axle. -->
<!-- And turned 20deg up! --> <!-- And turned 17deg up! -->
<joint name="axletocameraplate" type="fixed"> <joint name="axletocameraplate" type="fixed">
<parent link="axle"/> <parent link="axle"/>
<child link="cameraplate"/> <child link="cameraplate"/>
<origin xyz="0.15058 0 0.03633" rpy="0 -0.35 0"/> <origin xyz="0.15058 0 0.03633" rpy="0 -0.297 0"/>
</joint> </joint>
<link name="cameraplate"/> <link name="cameraplate"/>
...@@ -90,13 +90,4 @@ ...@@ -90,13 +90,4 @@
<link name="camera_link"/> <link name="camera_link"/>
<!-- Laser scanner (placed at camera but horizontal) -->
<joint name="cameratolaser" type="fixed">
<parent link="camera_link"/>
<child link="laser"/>
<origin xyz="0 0 0" rpy="0 0.35 0"/>
</joint>
<link name="laser"/>
</robot> </robot>
...@@ -71,11 +71,11 @@ ...@@ -71,11 +71,11 @@
<!-- which is -0.04875 behind the wheel axle. --> <!-- which is -0.04875 behind the wheel axle. -->
<!-- So shifted 0.05308 in front of the wheel axle. --> <!-- So shifted 0.05308 in front of the wheel axle. -->
<!-- Also Shifted 0.03633 above the wheel axle. --> <!-- Also Shifted 0.03633 above the wheel axle. -->
<!-- And turned 20deg up! --> <!-- And turned 17deg up! -->
<joint name="axletocameraplate" type="fixed"> <joint name="axletocameraplate" type="fixed">
<parent link="axle"/> <parent link="axle"/>
<child link="cameraplate"/> <child link="cameraplate"/>
<origin xyz="0.05308 0 0.03633" rpy="0 -0.35 0"/> <origin xyz="0.05308 0 0.03633" rpy="0 -0.297 0"/>
</joint> </joint>
<link name="cameraplate"/> <link name="cameraplate"/>
...@@ -90,13 +90,4 @@ ...@@ -90,13 +90,4 @@
<link name="camera_link"/> <link name="camera_link"/>
<!-- Laser scanner (placed at camera but horizontal) -->
<joint name="cameratolaser" type="fixed">
<parent link="camera_link"/>
<child link="laser"/>
<origin xyz="0 0 0" rpy="0 0.35 0"/>
</joint>
<link name="laser"/>
</robot> </robot>
Markdown is supported
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