diff --git a/ubr1_calibration/config/checkerboard_2d/calibrate.yaml b/ubr1_calibration/config/checkerboard_2d/calibrate.yaml new file mode 100644 index 0000000..0c80f97 --- /dev/null +++ b/ubr1_calibration/config/checkerboard_2d/calibrate.yaml @@ -0,0 +1,34 @@ +# This is a sample for testing the 2d checkerboard finder +# No part of the robot is actually being calibrated, +# It will simply find the checkerboard pose in the hand +robot_calibration: + ros__parameters: + verbose: true + base_link: torso_lift_link + calibration_steps: + - single_calibration_step + single_calibration_step: + models: + - arm + - camera + arm: + type: chain3d + frame: wrist_roll_link + camera: + type: camera2d + frame: head_camera_rgb_optical_frame + free_frames: + - checkerboard + checkerboard: + x: true + y: false + z: true + roll: true + pitch: true + yaw: true + error_blocks: + - hand_eye + hand_eye: + type: chain3d_to_camera2d + model_2d: camera + model_3d: arm diff --git a/ubr1_calibration/scripts/checkerboard_2d/checkerboard_2d_manually b/ubr1_calibration/scripts/checkerboard_2d/checkerboard_2d_manually index 1043276..c9ec7d3 100755 --- a/ubr1_calibration/scripts/checkerboard_2d/checkerboard_2d_manually +++ b/ubr1_calibration/scripts/checkerboard_2d/checkerboard_2d_manually @@ -1,4 +1,4 @@ #!/bin/bash # ros2 launch (from python) doesn't seem to pipe stdin to our node, so manual capture doesn't work -ros2 run robot_calibration calibrate --manual --ros-args --params-file ../../config/checkerboard_2d/capture.yaml --params-file ../../config/calibrate.yaml +ros2 run robot_calibration calibrate --manual --ros-args --params-file ../../config/checkerboard_2d/capture.yaml --params-file ../../config/checkerboard_2d/calibrate.yaml