7#include <Eigen/Geometry>
39template <camera_model CameraT>
58template <camera_model CameraT>
60 const std::vector<CameraT>& initial_cameras,
61 const std::vector<Eigen::Isometry3d>& init_g_se3_c,
62 const Eigen::Isometry3d& init_b_se3_t,
const BundleOptions& opts = {})
63 -> BundleResult<CameraT>;
65static_assert(serializable_aggregate<BundleOptions>);
66static_assert(serializable_aggregate<BundleObservation>);
Linear multi-camera extrinsics initialisation (DLT)
std::vector< PlanarObservation > PlanarView
auto optimize_bundle(const std::vector< BundleObservation > &observations, const std::vector< CameraT > &initial_cameras, const std::vector< Eigen::Isometry3d > &init_g_se3_c, const Eigen::Isometry3d &init_b_se3_t, const BundleOptions &opts={}) -> BundleResult< CameraT >
Perform bundle-adjustment style optimisation of the hand-eye calibration problem.
Single observation used for hand-eye calibration.
size_t camera_index
Which camera acquired this view.
Eigen::Isometry3d b_se3_g
Pose of the gripper in the base frame.
PlanarView view
Planar target observations.
Options controlling the hand-eye calibration optimisation.
OptimOptions core
Non-linear optimization options.
bool optimize_hand_eye
Solve for camera->gripper poses.
bool optimize_target_pose
Solve for base->target pose.
bool optimize_intrinsics
Solve for camera intrinsics.
bool optimize_skew
Solve for skew parameter.
Result returned by hand-eye calibration.
OptimResult core
Optimization result details.
std::vector< Eigen::Isometry3d > g_se3_c
Estimated camera->gripper extrinsics.
Eigen::Isometry3d b_se3_t
Pose of target in base frame.
std::vector< CameraT > cameras
Estimated camera parameters per camera.