Calibration Library 1.0.0
A C++ library for camera calibration and vision-related geometric transformations
Loading...
Searching...
No Matches
bundle.h
Go to the documentation of this file.
1#pragma once
2
3// std
4#include <vector>
5
6// eigen
7#include <Eigen/Geometry>
8
9#include "calib/estimation/linear/planarpose.h" // PlanarObservation
12
13namespace calib {
14
22struct BundleObservation final {
24 Eigen::Isometry3d b_se3_g;
25 size_t camera_index = 0;
26};
27
29// TODO: add optimize_distortion
30struct BundleOptions final {
31 OptimOptions core;
32 bool optimize_intrinsics = false;
33 bool optimize_skew = false;
35 bool optimize_hand_eye = true;
36};
37
39template <camera_model CameraT>
40struct BundleResult final {
42 std::vector<CameraT> cameras;
43 std::vector<Eigen::Isometry3d> g_se3_c;
44 Eigen::Isometry3d b_se3_t;
45};
46
58template <camera_model CameraT>
59auto optimize_bundle(const std::vector<BundleObservation>& observations,
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>;
64
65static_assert(serializable_aggregate<BundleOptions>);
66static_assert(serializable_aggregate<BundleObservation>);
67
68} // namespace calib
Linear multi-camera extrinsics initialisation (DLT)
std::vector< PlanarObservation > PlanarView
Definition planarpose.h:26
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.
Definition bundle.cpp:148
Single observation used for hand-eye calibration.
Definition bundle.h:22
size_t camera_index
Which camera acquired this view.
Definition bundle.h:25
Eigen::Isometry3d b_se3_g
Pose of the gripper in the base frame.
Definition bundle.h:24
PlanarView view
Planar target observations.
Definition bundle.h:23
Options controlling the hand-eye calibration optimisation.
Definition bundle.h:30
OptimOptions core
Non-linear optimization options.
Definition bundle.h:31
bool optimize_hand_eye
Solve for camera->gripper poses.
Definition bundle.h:35
bool optimize_target_pose
Solve for base->target pose.
Definition bundle.h:34
bool optimize_intrinsics
Solve for camera intrinsics.
Definition bundle.h:32
bool optimize_skew
Solve for skew parameter.
Definition bundle.h:33
Result returned by hand-eye calibration.
Definition bundle.h:40
OptimResult core
Optimization result details.
Definition bundle.h:41
std::vector< Eigen::Isometry3d > g_se3_c
Estimated camera->gripper extrinsics.
Definition bundle.h:43
Eigen::Isometry3d b_se3_t
Pose of target in base frame.
Definition bundle.h:44
std::vector< CameraT > cameras
Estimated camera parameters per camera.
Definition bundle.h:42