Skip to content

Commit

Permalink
add configuration to calibrate pose of checkerboard with 2d camera
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed May 17, 2023
1 parent 06587cc commit d61df58
Show file tree
Hide file tree
Showing 2 changed files with 35 additions and 1 deletion.
34 changes: 34 additions & 0 deletions 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
@@ -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

0 comments on commit d61df58

Please sign in to comment.