#include "calib/estimation/optim/handeye.h"
#include <array>
#include <stdexcept>
#include <vector>
#include <ceres/ceres.h>
#include "detail/ceresutils.h"
#include "detail/observationutils.h"
#include "residuals/handeyeresidual.h"
Go to the source code of this file.
|
| namespace | calib |
| | Linear multi-camera extrinsics initialisation (DLT)
|
| |
|
| static auto | calib::build_problem (const std::vector< MotionPair > &pairs, const OptimOptions &opts, HandeyeBlocks &blocks) -> ceres::Problem |
| |
| auto | calib::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.
|
| |
| auto | calib::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.
|
| |