17#include <Eigen/Geometry>
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,
57 bool reject_axis_parallel =
true,
58 double axis_parallel_eps = 1e-3) -> std::vector<MotionPair>;
89 const std::vector<Eigen::Isometry3d>& camera_se3_target,
90 double min_angle_deg = 1.0) -> Eigen::Isometry3d;
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.
Eigen::Matrix3d rot_b
Rotation matrices for motions A and B.
Eigen::Vector3d tra_b
Translation vectors for motions A and B.