Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Hydro Updates #51

Merged
merged 12 commits into from
Apr 28, 2014
8 changes: 4 additions & 4 deletions raw3-1/calibration/cameras/left.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,17 @@ image_height: 1024
camera_matrix:
rows: 3
cols: 3
data: [1451.2239242707201, 0.0, 647.33159357949535, 0.0, 1451.512357466929, 505.19364095186694, 0.0, 0.0, 1.0]
data: [2478.10117, 0.0, 676.94299, 0.0, 2480.12385, 500.31739, 0.0, 0.0, 1.0]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.25648209827532603, 0.21535276176875215, -0.00076700926780839441, -0.0010578565343022676, -0.053446645001753126]
data: [-0.11020, 0.13941, -0.00081, -0.00164, 0.00000]
rectification_matrix:
rows: 3
cols: 3
data: [0.99992009750099486, 0.0079444814385283887, -0.0098327935132465714, -0.0079216726602033809, 0.99996584655826892, 0.002356442078415095, 0.0098511783998591895, -0.0022783616212569972, 0.99994888036962026]
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
projection_matrix:
rows: 3
cols: 4
data: [1455.1678151992817, 0.0, 663.18903350830078, 0.0, 0.0, 1455.1678151992817, 509.86345291137695, 0.0, 0.0, 0.0, 1.0, 0.0]
data: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0]
13 changes: 6 additions & 7 deletions raw3-1/calibration/cameras/right.yaml
Original file line number Diff line number Diff line change
@@ -1,22 +1,21 @@
camera_name: right
frame_id: /head_color_camera_l_link
image_width: 1360
frame_id: /head_color_camera_r_link
image_width: 1024
image_height: 1024
camera_matrix:
rows: 3
cols: 3
data: [1446.21137, 0.0, 663.37706, 0.0, 1441.56567, 525.39049, 0.0, 0.0, 1.0]
data: [1680.427850, 0.000000, 519.168401, 0.000000, 1680.703878, 489.716604, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.25773, 0.20704, -0.00061, -0.00063, 0.00000]
data: [-0.267916, 0.275592, 0.000280, 0.000391, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
# data: [0.99996690524286469, -0.0038442590186795254, 0.007170083096109235, 0.0038608651288062818, 0.99998989346341471, -0.0023036257259529034, -0.00716115489742946, 0.0023312322118153451, 0.99997164120634441]
data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
projection_matrix:
rows: 3
cols: 4
data: [1446.21137, 0.0, 663.37706, 0.0, 0.0, 1441.56567, 525.39049, 0.0, 0.0, 0.0, 1.0, 0.0]
data: [1680.427850, 0.000000, 519.168401, 0.000000, 0.000000, 1680.703878, 489.716604, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
48 changes: 48 additions & 0 deletions raw3-3/calibration/calibration_offset.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,52 @@
<property name="offset_gripper_right_pitch" value="0.0"/>
<property name="offset_gripper_right_yaw" value="0.0"/>

<!-- neck mount positions | relative to arm_torso_link -->
<property name="offset_neck_x" value="0.0"/>
<property name="offset_neck_y" value="0.0"/>
<property name="offset_neck_z" value="0.0"/>
<property name="offset_neck_roll" value="0.0"/>
<property name="offset_neck_pitch" value="0.0"/>
<property name="offset_neck_yaw" value="0.0"/>

<!-- head mount positions | relative to neck_mount_link -->
<property name="offset_head_x" value="0.0"/>
<property name="offset_head_y" value="0.0"/>
<property name="offset_head_z" value="0.0"/>
<property name="offset_head_roll" value="0.0"/>
<property name="offset_head_pitch" value="0.0"/>
<property name="offset_head_yaw" value="0.0"/>

<!-- ids_middle mount positions | relative to head_cam_holder_link -->
<property name="offset_ids_middle_x" value="0.0"/>
<property name="offset_ids_middle_y" value="0.0"/>
<property name="offset_ids_middle_z" value="0.0"/>
<property name="offset_ids_middle_roll" value="0.0"/>
<property name="offset_ids_middle_pitch" value="0.0"/>
<property name="offset_ids_middle_yaw" value="0.0"/>

<!-- ids_left mount positions | relative to head_cam_holder_link -->
<property name="offset_ids_left_x" value="0.0"/>
<property name="offset_ids_left_y" value="0.0"/>
<property name="offset_ids_left_z" value="0.0"/>
<property name="offset_ids_left_roll" value="0.0"/>
<property name="offset_ids_left_pitch" value="0.0"/>
<property name="offset_ids_left_yaw" value="0.0"/>

<!-- ids_right mount positions | relative to head_cam_holder_link -->
<property name="offset_ids_right_x" value="0.0"/>
<property name="offset_ids_right_y" value="0.0"/>
<property name="offset_ids_right_z" value="0.0"/>
<property name="offset_ids_right_roll" value="0.0"/>
<property name="offset_ids_right_pitch" value="0.0"/>
<property name="offset_ids_right_yaw" value="0.0"/>

<!-- cam_holder mount positions | relative to head_cam_holder_link -->
<property name="offset_cam_holder_x" value="0.0"/>
<property name="offset_cam_holder_y" value="0.0"/>
<property name="offset_cam_holder_z" value="0.0"/>
<property name="offset_cam_holder_roll" value="0.0"/>
<property name="offset_cam_holder_pitch" value="0.0"/>
<property name="offset_cam_holder_yaw" value="0.0"/>

</robot>