17 std::optional<CalibrationBounds>
bounds = std::nullopt;
22template <camera_model CameraT>
33 -> IntrinsicsOptimizationResult<PinholeCamera<BrownConradyd>>;
35template <camera_model CameraT>
37 std::vector<Eigen::Isometry3d> init_c_se3_t,
38 const IntrinsicsOptimOptions& opts = {})
39 -> IntrinsicsOptimizationResult<CameraT>;
41static_assert(serializable_aggregate<IntrinsicsOptimOptions>);
Linear multi-camera extrinsics initialisation (DLT)
auto optimize_intrinsics_semidlt(const std::vector< PlanarView > &views, const CameraMatrix &initial_guess, const IntrinsicsOptimOptions &opts={}) -> IntrinsicsOptimizationResult< PinholeCamera< BrownConradyd > >
auto optimize_intrinsics(const std::vector< PlanarView > &views, const CameraT &init_camera, std::vector< Eigen::Isometry3d > init_c_se3_t, const IntrinsicsOptimOptions &opts={}) -> IntrinsicsOptimizationResult< CameraT >
OptimOptions core
Non-linear optimization options.
std::optional< CalibrationBounds > bounds
Parameter bounds.
int num_radial
Number of radial distortion coefficients.
bool optimize_skew
Estimate skew parameter.
std::vector< double > fixed_distortion_values
Assigned fixed values.
std::vector< int > fixed_distortion_indices
Indices of coeffs to keep fixed.
OptimResult core
Optimization result details.
CameraT camera
Estimated camera parameters.
std::vector< Eigen::Isometry3d > c_se3_t
Estimated pose of each view.
std::vector< double > view_errors
Per-view reprojection errors.