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

setup cob4-8 #131

Merged
merged 2 commits into from
Jun 14, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
135 changes: 135 additions & 0 deletions cob4-8/calibration/calibration_offset.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,135 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- ***************** -->
<!-- base calibration -->
<!-- ***************** -->
<!-- laser front mount positions | relative to base_link -->
<xacro:property name="offset_laser_front_x" value="0.0"/>
<xacro:property name="offset_laser_front_y" value="0.0"/>
<xacro:property name="offset_laser_front_z" value="0.0"/>
<xacro:property name="offset_laser_front_roll" value="0.0"/>
<xacro:property name="offset_laser_front_pitch" value="0.0"/>
<xacro:property name="offset_laser_front_yaw" value="0.0"/>

<!-- laser rear mount positions | relative to base_link -->
<xacro:property name="offset_laser_left_x" value="0.0"/>
<xacro:property name="offset_laser_left_y" value="0.0"/>
<xacro:property name="offset_laser_left_z" value="0.0"/>
<xacro:property name="offset_laser_left_roll" value="0.0"/>
<xacro:property name="offset_laser_left_pitch" value="0.0"/>
<xacro:property name="offset_laser_left_yaw" value="0.0"/>

<!-- laser top mount positions | relative to base_link -->
<xacro:property name="offset_laser_right_x" value="0.0"/>
<xacro:property name="offset_laser_right_y" value="0.0"/>
<xacro:property name="offset_laser_right_z" value="0.0"/>
<xacro:property name="offset_laser_right_roll" value="0.0"/>
<xacro:property name="offset_laser_right_pitch" value="0.0"/>
<xacro:property name="offset_laser_right_yaw" value="0.0"/>

<!-- *********************** -->
<!-- upper robot calibration -->
<!-- *********************** -->

<!-- torso mount positions | relative to base_link -->
<xacro:property name="offset_torso_x" value="0.0"/>
<xacro:property name="offset_torso_y" value="0.0"/>
<xacro:property name="offset_torso_z" value="0.0"/>
<xacro:property name="offset_torso_roll" value="0.0"/>
<xacro:property name="offset_torso_pitch" value="0.0"/>
<xacro:property name="offset_torso_yaw" value="0.0"/>

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

<!-- sersorring mount positions | relative to head_3_link -->
<xacro:property name="offset_sensorring_x" value="0.0"/>
<xacro:property name="offset_sensorring_y" value="0.0"/>
<xacro:property name="offset_sensorring_z" value="0.0"/>
<xacro:property name="offset_sensorring_roll" value="0.0"/>
<xacro:property name="offset_sensorring_pitch" value="0.0"/>
<xacro:property name="offset_sensorring_yaw" value="0.0"/>

<!-- arm right mount positions | relative to torso_3_link -->
<xacro:property name="offset_arm_right_x" value="0.0"/>
<xacro:property name="offset_arm_right_y" value="0.0"/>
<xacro:property name="offset_arm_right_z" value="0.0"/>
<xacro:property name="offset_arm_right_roll" value="0.0"/>
<xacro:property name="offset_arm_right_pitch" value="0.0"/>
<xacro:property name="offset_arm_right_yaw" value="0.0"/>

<!-- arm left mount positions | relative to torso_3_link -->
<xacro:property name="offset_arm_left_x" value="0.0"/>
<xacro:property name="offset_arm_left_y" value="0.0"/>
<xacro:property name="offset_arm_left_z" value="0.0"/>
<xacro:property name="offset_arm_left_roll" value="0.0"/>
<xacro:property name="offset_arm_left_pitch" value="0.0"/>
<xacro:property name="offset_arm_left_yaw" value="0.0"/>

<!-- gripper right mount positions | relative to arm_7_link -->
<xacro:property name="offset_gripper_right_x" value="0.0"/>
<xacro:property name="offset_gripper_right_y" value="0.0"/>
<xacro:property name="offset_gripper_right_z" value="0.0"/>
<xacro:property name="offset_gripper_right_roll" value="0.0"/>
<xacro:property name="offset_gripper_right_pitch" value="0.0"/>
<xacro:property name="offset_gripper_right_yaw" value="0.0"/>

<!-- gripper left mount positions | relative to arm_7_link -->
<xacro:property name="offset_gripper_left_x" value="0.0"/>
<xacro:property name="offset_gripper_left_y" value="0.0"/>
<xacro:property name="offset_gripper_left_z" value="0.0"/>
<xacro:property name="offset_gripper_left_roll" value="0.0"/>
<xacro:property name="offset_gripper_left_pitch" value="0.0"/>
<xacro:property name="offset_gripper_left_yaw" value="0.0"/>

<!-- *********************************** -->
<!-- kinematic chain reference positions -->
<!-- *********************************** -->
<!-- this feature is no longer supported as urdfdom does not parse the according 'calibration_rising' tag -->

<!-- cam3d left | handeye calibration | relative to torso_3_link -->
<xacro:property name="offset_torso_cam3d_left_x" value="0.0"/>
<xacro:property name="offset_torso_cam3d_left_y" value="0.025"/>
<xacro:property name="offset_torso_cam3d_left_z" value="0.0"/>
<xacro:property name="offset_torso_cam3d_left_roll" value="0.0"/>
<xacro:property name="offset_torso_cam3d_left_pitch" value="0.0"/>
<xacro:property name="offset_torso_cam3d_left_yaw" value="0.05"/>

<!-- cam3d right | handeye calibration | relative to torso_3_link -->
<xacro:property name="offset_torso_cam3d_right_x" value="0.0"/>
<xacro:property name="offset_torso_cam3d_right_y" value="0.0"/>
<xacro:property name="offset_torso_cam3d_right_z" value="0.0"/>
<xacro:property name="offset_torso_cam3d_right_roll" value="0.0"/>
<xacro:property name="offset_torso_cam3d_right_pitch" value="0.0"/>
<xacro:property name="offset_torso_cam3d_right_yaw" value="0.05"/>

<!-- cam3d down | handeye calibration | relative to torso_3_link -->
<xacro:property name="offset_torso_cam3d_down_x" value="0.0"/>
<xacro:property name="offset_torso_cam3d_down_y" value="0.0"/>
<xacro:property name="offset_torso_cam3d_down_z" value="0.0"/>
<xacro:property name="offset_torso_cam3d_down_roll" value="0.0"/>
<xacro:property name="offset_torso_cam3d_down_pitch" value="0.0"/>
<xacro:property name="offset_torso_cam3d_down_yaw" value="0.0"/>

<!-- cam3d | handeye calibration | relative to sensorring_link -->
<xacro:property name="offset_sensorring_cam3d_x" value="0.0"/>
<xacro:property name="offset_sensorring_cam3d_y" value="0.0"/>
<xacro:property name="offset_sensorring_cam3d_z" value="0.0"/>
<xacro:property name="offset_sensorring_cam3d_roll" value="0.0"/>
<xacro:property name="offset_sensorring_cam3d_pitch" value="0.0"/>
<xacro:property name="offset_sensorring_cam3d_yaw" value="0.0"/>


<!-- cam | handeye calibration | relative to head_3_link -->
<xacro:property name="offset_head_cam_x" value="0.0"/>
<xacro:property name="offset_head_cam_y" value="0.0"/>
<xacro:property name="offset_head_cam_z" value="0.0"/>
<xacro:property name="offset_head_cam_roll" value="0.0"/>
<xacro:property name="offset_head_cam_pitch" value="0.0"/>
<xacro:property name="offset_head_cam_yaw" value="0.0"/>
</robot>
20 changes: 20 additions & 0 deletions cob4-8/calibration/cameras/head_cam.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
image_width: 2048
image_height: 1536
camera_name: head_cam
camera_matrix:
rows: 3
cols: 3
data: [904.252829, 0.000000, 1087.269448, 0.000000, 900.406778, 647.191021, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.287932, 0.050694, 0.001883, -0.005138, 0.000000]
rectification_matrix:
rows: 3
cols: 3
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: [626.475708, 0.000000, 1091.475787, 0.000000, 0.000000, 672.085632, 608.905349, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]