-
Notifications
You must be signed in to change notification settings - Fork 116
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
ROS 2 Branch - Checkerboard Finder + Hand Eye Calibration #149
Comments
Parameter Overrides Issues Should I override the following parameters somewhere? robot_calibration/robot_calibration/include/robot_calibration/util/depth_camera_info.hpp Line 43 in 12608c6
robot_calibration/robot_calibration/include/robot_calibration/util/depth_camera_info.hpp Line 53 in 12608c6
I have observed warning such as the following warning due to these hardcoded defaults
These issues are resolved when I change the default to a value that is appropriate for my setup. Checkboard size
|
Yes - you want to set "camera_info_topic" in the same spot you set "topic" (under "checkerboard_finder" namespace) The parameters for any of the individual finders really aren't documented outside of the code (other than example configs - which probably should have ALL the parameters added to them) - tutorial/readme updates greatly appreciated. |
Thanks @mikeferguson for the response on this. Checkerboard Finder
I have just tried this and it didn't work for me, you mean set it in the Optimization
This package is awesome, one question I had as I am delving into the code some more, is it assumed that the camera link and robot base link are initially part of the same kinematic tree. For a robot platform with integrated camera this will be the case but for a setup like the one I have the camera is mounted on a tripod and I don't have an accurate transform from the robot base link to the camera base link. As a result I cannot construct a chain and hence I run into the above error. I could publish a dummy transform to the link and calibrate its child joint as a free frame, I think this will work. What are your thoughts @mikeferguson, did I overlook something? I am performing Hand Eye calibration on the following setup. |
I am still getting the following error:
I added a dummy static transform so the camera is now connected to the base of the robot. Here is tf output from rviz that demonstrates this: Any guidance would be appreciated, I am going to review my config for a typo and begin creating a sequence of prespecified poses before continuing to debug this. |
This would actually go in the "capture.yaml" - there are two steps here, capture and then calibration. During capture, we are using the various finders, during calibration we are using the various models to reproject the data we captured. Once we get to the calibration step, we don't care about topics anymore (the data is already captured in the form of calibration_data messages). So your capture.yaml would look like:
|
Thank you, silly mistake on my part. |
The output of calibration is an update URDF - so anything we want to modify has to be in the URDF (also, internally, we use KDL, not TF, so any part of the chain has to be in the URDF). Are you publishing this dummy frame with the TF static_transform_publisher? If so, you need to add the camera to your URDF and then things should hopefully run! |
This makes sense, I was just starting to look into the use of Thanks for your help, I'll be sure to close this issue once I update my setup and have it running. I'll also look to contribute to the README.md. I'm happy to potentially make other contributions in future now I am getting more familiar with this codebase. |
One additional comment on capture vs. calibration - just for completeness - that "topic" part in your calibration.yaml is unused (topic isn't a parameter of the camera3d model) |
This is good to know, I am also going to look into how parameters are being handled in the code so that I improve my understanding of the codebase. Thank you. |
The changes you suggested addressed the issue relating to constructing a frame which I was facing. In my case I approximate the transform between the camera base and the robot base with real-world measurements and add as these as the origin of the realsense in my URDF. My script for collecting joint positions is ready so I can generate a large number of feasible configurations to use for the automatic calibration utilities. When I run calibrate with 20 manually collected samples the Ceres solver is failing due to Nans in the residuals. I will start exploring this side of things this evening, hopefully will have a calibrated camera frame by today/tomorrow. Looking forward to also trying to calibrate robot kinematics. |
Converged but to very inaccurate results, making progress nonetheless. Thanks for your help so far, I'm going to clean my workspace and code and revisit this tomorrow. I'll try to post a pr with further documentation by this week or early next week should I get to accurate results. |
With only 20 samples, and 2 completely free frames, that probably won't converge - a couple possible ways to improve:
One really big caveat with roll/pitch/yaw to remember: you can have 0, 1, or 3 free parameters - but never 2 (because internally it is specified as angle-axis and so we can limit the rotation to a single roll/pitch/yaw - but can't properly specify, for example, roll+pitch but no yaw movement) |
As in for the initial values of the free frame or the accuracy of the value defined in the URDF? |
The combination of the two (the free_frame initial values simply add/subtract to the URDF defined values - at runtime, they are indistinguishable when the transforms are calculated by KDL) |
I updated my setup based on the above feedback by clamping the board with the gripper I have. This allowed me to update the set of free parameters in a similar fashion to the UBR-1 example you gave. Despite this, I have still not been able to get the solver to converge to a correct result. I have provided further details below, it would be appreciated if you could take a quick glance in case you spot something that is awry. Robot Workspace Config Files robot_calibration:
ros__parameters:
chains:
- arm
arm:
topic: /panda_arm_controller/follow_joint_trajectory
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7
features:
- checkerboard_finder
checkerboard_finder:
type: robot_calibration::CheckerboardFinder
topic: /camera/depth/color/points
camera_info_topic: /camera/depth/camera_info
points_x: 9
points_y: 6
size: 0.0245
camera_sensor_name: camera
chain_sensor_name: arm robot_calibration:
ros__parameters:
verbose: true
base_link: panda_link0
calibration_steps:
- single_calibration_step
single_calibration_step:
models:
- arm
- camera
arm:
type: chain3d
frame: panda_link8
camera:
type: camera3d
frame: camera_color_optical_frame
topic: /camera/depth/color/points
free_frames:
- camera_joint
- checkerboard
camera_joint:
x: true
y: true
z: true
roll: true
pitch: true
yaw: true
checkerboard:
x: true
y: false
z: true
roll: false
pitch: true
yaw: false
free_frames_initial_values:
- camera_joint
- checkerboard
camera_joint_initial_values:
x: 1.6
y: 0.0
z: 0.6
roll: 0.0
pitch: 0.0
yaw: 3.142
checkerboard_initial_values:
x: 0.0
y: 0.0
z: 0.25
roll: 0.0
pitch: 0.0
yaw: 1.571
error_blocks:
- hand_eye
- restrict_camera
- restrict_checkerboard
hand_eye:
type: chain3d_to_chain3d
model_a: camera
model_b: arm
restrict_camera:
type: outrageous
param: camera_joint
joint_scale: 0.0
position_scale: 0.1
rotation_scale: 0.1
restrict_checkerboard:
type: outrageous
param: checkerboard
joint_scale: 0.0
position_scale: 0.1
rotation_scale: 0.1 Solver Output
Next Steps
|
This line looks suspect to me:
That should say "Adding chain3d_to_chain3d: hand_eye" and then have two more lines - but it looks like your YAML is misformatted and the restrict_camera/checkerboard are indented too many lines and getting tacked onto the name (which then doesn't exist) so you have NO error blocks... For reference - this error message pops up here: https://github.com/mikeferguson/robot_calibration/blob/ros2/robot_calibration/src/optimization/params.cpp#L101 It looks like we should have an error for several issues that are creeping up here:
|
I created #150 - which adds the better error messages above |
@mikeferguson thank you, that was likely the issue, for small samples I now seem to be getting ballpark correct results when I ensure my config files are correctly formatted. When running on a large batch of data I encounter nans, I need to identify why this is the case, I am going to start with cost function evaluation. I am going to start to document my setup for others to also perform hand-eye calibration, I was considering opening a pr that adds an examples folder to the root of this repository and include a description for hand-eye with a README.md that outlines my current configuration. If I get time I will add a simulated setup. Does this sound like a reasonable contribution? Also thanks for your responsiveness to my questions thus far. I still wish to work on my setup to ensure I am getting accurately calibrate results but will start documenting in the meantime as well. |
I have a question concerning the definition of a checkerboard frame within a 3D context, specifically when configuring it in a URDF file. How should this frame be accurately defined? Is it standard practice to set the origin at the top left inner corner of the checkerboard, with the X-axis aligned along the rows and the Y-axis aligned along the columns? |
Hey dude, I think it is dependent on the software library and conventions it sets. It has been a while since I have looked at this set of software but from what I recall it leverages opencv only for detecting corners. From what I remember opencv has the Z-axis pointing perpendicular to the target pointing away from the target surface (i.e. towards camera detecting target). I cannot recall the axis alignment along the board, the following tutorial has an example of plotting frames but I don't think it explicitly calls out axis alignment conventions for opencv. It might be possible to glean this information from the source code or the opencv docs, off the top of my head I don't 100% recall the convention, the linked tutorial aligns with your suggestion for the axis convention. |
Assuming you have an asymmetric checkerboard, then the side connecting the black corners is your "left" side, and the intersections are ordered such that the lower left is the first intersection. There is a big comment in chain3d that shows the ordering of what gets kicked out (although I'm not sure that the X/Y axis labeling matches OpenCV)
(also note, in reviewing this, I found that the coordinate frames in the comment were out of date with what we used internally - updated in #160) |
Hi @mikeferguson,
I am looking to perform hand-eye calibration of a realsense depth camera in my scene (containing a Franka Emika Panda) using this package. I am trying to estimate the transform between my robot base
panda_link0
and the framecamera_depth_optical_frame
. I have mounted a checkerboard on my robot eef and provided an initial guess for the checkboard frame transform as part of my configuration files.So far capturing samples works great for me on ROS 2.
I am however facing an error when running the optimization step; the error relates to building a chain model. I have been able to capture samples but when I look to run the optimization step I get the following error:
Error source
Called From
The link names appear to be correct based on the models I am loading. My understanding is that I have the transform from my
camera_depth_optical_frame
->checkerboard
and transforms frompanda_link0
->panda_link8
while I have an initial estimate forpanda_link8
->checkerboard
. This information should be sufficient based on my understanding to get a reasonable calibration given enough samples of data.My configuration files are as follows:
I am happy to write up/contribute to the README or a tutorial once I get this working.
The text was updated successfully, but these errors were encountered: