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
11#pragma once
12
13// std
14#include <vector>
15
16// eigen
17#include <Eigen/Geometry>
18
21
22namespace calib {
23
34struct MotionPair final {
35 Eigen::Matrix3d rot_a, rot_b;
36 Eigen::Vector3d tra_a, tra_b;
37};
38
54auto build_all_pairs(const std::vector<Eigen::Isometry3d>& base_se3_gripper,
55 const std::vector<Eigen::Isometry3d>& cam_se3_target,
56 double min_angle_deg = 1.0, // discard too-small motions
57 bool reject_axis_parallel = true, // guard against ill-conditioning
58 double axis_parallel_eps = 1e-3) -> std::vector<MotionPair>;
59
88auto estimate_handeye_dlt(const std::vector<Eigen::Isometry3d>& base_se3_gripper,
89 const std::vector<Eigen::Isometry3d>& camera_se3_target,
90 double min_angle_deg = 1.0) -> Eigen::Isometry3d;
91
93
94} // namespace calib
Linear multi-camera extrinsics initialisation (DLT)
auto estimate_handeye_dlt(const std::vector< Eigen::Isometry3d > &base_se3_gripper, const std::vector< Eigen::Isometry3d > &camera_se3_target, double min_angle_deg=1.0) -> Eigen::Isometry3d
Estimates the hand-eye transformation using the Tsai-Lenz algorithm with all pairs of input transform...
auto build_all_pairs(const std::vector< Eigen::Isometry3d > &base_se3_gripper, const std::vector< Eigen::Isometry3d > &cam_se3_target, double min_angle_deg=1.0, bool reject_axis_parallel=true, double axis_parallel_eps=1e-3) -> std::vector< MotionPair >
Generate all valid motion pairs from pose sequences.
Motion pair structure for hand-eye calibration.
Definition handeye.h:34
Eigen::Vector3d tra_a
Definition handeye.h:36
Eigen::Matrix3d rot_b
Rotation matrices for motions A and B.
Definition handeye.h:35
Eigen::Vector3d tra_b
Translation vectors for motions A and B.
Definition handeye.h:36
Eigen::Matrix3d rot_a
Definition handeye.h:35