Calibration Library 1.0.0
A C++ library for camera calibration and vision-related geometric transformations
Loading...
Searching...
No Matches
handeye.h
Go to the documentation of this file.
1
9#pragma once
10
13
14namespace calib {
15
16struct HandeyeResult final {
18 Eigen::Isometry3d g_se3_c;
19};
20
40auto optimize_handeye(const std::vector<Eigen::Isometry3d>& base_se3_gripper,
41 const std::vector<Eigen::Isometry3d>& camera_se3_target,
42 const Eigen::Isometry3d& init_gripper_se3_ref,
43 const OptimOptions& options = {}) -> HandeyeResult;
44
64auto estimate_and_optimize_handeye(const std::vector<Eigen::Isometry3d>& base_se3_gripper,
65 const std::vector<Eigen::Isometry3d>& camera_se3_target,
66 double min_angle_deg = 1.0, const OptimOptions& options = {})
67 -> HandeyeResult;
68
69} // namespace calib
Hand-eye calibration algorithms and utilities.
Linear multi-camera extrinsics initialisation (DLT)
auto optimize_handeye(const std::vector< Eigen::Isometry3d > &base_se3_gripper, const std::vector< Eigen::Isometry3d > &camera_se3_target, const Eigen::Isometry3d &init_gripper_se3_ref, const OptimOptions &options={}) -> HandeyeResult
Refines the hand-eye calibration transformation using an optimization process.
Definition handeye.cpp:60
auto estimate_and_optimize_handeye(const std::vector< Eigen::Isometry3d > &base_se3_gripper, const std::vector< Eigen::Isometry3d > &camera_se3_target, double min_angle_deg=1.0, const OptimOptions &options={}) -> HandeyeResult
Estimates and refines the hand-eye transformation.
Definition handeye.cpp:80
Eigen::Isometry3d g_se3_c
Estimated hand-eye transform (gripper -> camera)
Definition handeye.h:18
OptimResult core
Core optimization result.
Definition handeye.h:17