7#include <unordered_map>
28 std::vector<PipelineStageResult>
stages;
37 bool has_intrinsics_config_{
false};
39 bool has_stereo_config_{
false};
41 bool has_handeye_config_{
false};
43 bool has_bundle_config_{
false};
48 std::unordered_map<std::string, ExtrinsicOptimizationResult<PinholeCamera<BrownConradyd>>>
50 std::unordered_map<std::string, std::unordered_map<std::string, HandeyeResult>>
handeye_results;
51 std::unordered_map<std::string, BundleResult<PinholeCamera<BrownConradyd>>>
bundle_results;
60 return intrinsics_config_;
65 return stereo_config_;
70 return handeye_config_;
75 return bundle_config_;
83 [[nodiscard]]
virtual auto name() const -> std::
string = 0;
102 std::vector<std::unique_ptr<CalibrationStage>> stages_;
103 std::vector<std::shared_ptr<StageDecorator>> decorators_;
106 void add_stage(std::unique_ptr<CalibrationStage> stage);
107 void add_decorator(std::shared_ptr<StageDecorator> decorator);
virtual ~CalibrationStage()=default
virtual auto name() const -> std::string=0
virtual auto run(PipelineContext &context) -> PipelineStageResult=0
virtual ~DatasetLoader()=default
virtual auto load() -> CalibrationDataset=0
LoggingDecorator(std::ostream &out)
void set_intrinsics_config(IntrinsicCalibrationConfig cfg)
auto has_handeye_config() const -> bool
auto has_intrinsics_config() const -> bool
void set_handeye_config(HandEyePipelineConfig cfg)
std::unordered_map< std::string, ExtrinsicOptimizationResult< PinholeCamera< BrownConradyd > > > stereo_results
void set_stereo_config(StereoCalibrationConfig cfg)
CalibrationDataset dataset
auto stereo_config() const -> const StereoCalibrationConfig &
auto intrinsics_config() const -> const IntrinsicCalibrationConfig &
auto handeye_config() -> HandEyePipelineConfig &
std::unordered_map< std::string, std::unordered_map< std::string, HandeyeResult > > handeye_results
std::unordered_map< std::string, IntrinsicCalibrationOutputs > intrinsic_results
auto handeye_config() const -> const HandEyePipelineConfig &
std::unordered_map< std::string, BundleResult< PinholeCamera< BrownConradyd > > > bundle_results
auto bundle_config() const -> const BundlePipelineConfig &
void set_bundle_config(BundlePipelineConfig cfg)
auto has_stereo_config() const -> bool
auto has_bundle_config() const -> bool
auto bundle_config() -> BundlePipelineConfig &
auto stereo_config() -> StereoCalibrationConfig &
auto intrinsics_config() -> IntrinsicCalibrationConfig &
virtual void before_stage(const CalibrationStage &, PipelineContext &)
virtual ~StageDecorator()=default
virtual void after_stage(const CalibrationStage &, PipelineContext &, const PipelineStageResult &)
Hand-eye calibration algorithms and utilities.
Pipeline configuration helpers for hand-eye and bundle adjustment stages.
Aggregated dataset consumed by the calibration pipeline.
std::vector< PipelineStageResult > stages