Ceres
Algorithm Implementations
bundle_adjust
-
class bundle_adjust : public kwiver::vital::algo::bundle_adjust
A class for bundle adjustment of feature tracks using Ceres.
Public Functions
- PLUGGABLE_IMPL (bundle_adjust, "Uses Ceres Solver to bundle adjust camera and landmark parameters.", PARAM_DEFAULT(verbose, bool, "If true, write status messages to the terminal showing " "optimization progress at each iteration.", false), PARAM_DEFAULT(log_full_report, bool, "If true, log a full report of optimization stats at " "the end of optimization.", false), PARAM_DEFAULT(loss_function_type, LossFunctionType, "Robust loss function type to use.", TRIVIAL_LOSS), PARAM_DEFAULT(loss_function_scale, double, "Robust loss function scale factor.", 1.0), PARAM(solver_options, solver_options_sptr, "pointer to the nested config options for solver"), PARAM(camera_options, camera_options_sptr, "pointer to the nested config options for camera")) virtual ~bundle_adjust()=default
Destructor.
-
virtual bool check_configuration(vital::config_block_sptr config) const
Check that the algorithm’s currently configuration is valid.
-
virtual void optimize(vital::camera_map_sptr &cameras, vital::landmark_map_sptr &landmarks, vital::feature_track_set_sptr tracks, vital::sfm_constraints_sptr constraints = nullptr) const
Optimize the camera and landmark parameters given a set of tracks.
Optimize the camera and landmark parameters given a set of feature tracks
- Parameters:
cameras – [inout] The cameras to optimize.
landmarks – [inout] The landmarks to optimize.
tracks – [in] The feature tracks to use as constraints.
metadata – [in] The frame metadata to use as constraints.
-
virtual void optimize(kwiver::vital::simple_camera_perspective_map &cameras, kwiver::vital::landmark_map::map_landmark_t &landmarks, vital::feature_track_set_sptr tracks, const std::set<vital::frame_id_t> &fixed_cameras, const std::set<vital::landmark_id_t> &fixed_landmarks, kwiver::vital::sfm_constraints_sptr constraints = nullptr) const
Optimize the camera and landmark parameters given a set of feature tracks
- Parameters:
cameras – [inout] the cameras to optimize
landmarks – [inout] the landmarks to optimize
tracks – [in] the feature tracks to use as constraints
fixed_cameras – [in] frame ids for cameras to be fixed in the optimization
fixed_landmarks – [in] landmark ids for landmarks to be fixed in the optimization
metadata – [in] the frame metadata to use as constraints
-
virtual void set_callback(callback_t cb)
Set a callback function to report intermediate progress.
-
bool trigger_callback()
This function is called by a Ceres callback to trigger a kwiver callback.
optimize_cameras
-
class optimize_cameras : public kwiver::vital::algo::optimize_cameras
A class for optimization of camera paramters using Ceres.
Public Functions
- PLUGGABLE_IMPL (optimize_cameras, "Uses Ceres Solver to optimize camera parameters", PARAM_DEFAULT(verbose, bool, "If true, write status messages to the terminal showing " "optimization progress at each iteration", false), PARAM_DEFAULT(loss_function_type, LossFunctionType, "Robust loss function type to use.", TRIVIAL_LOSS), PARAM_DEFAULT(loss_function_scale, double, "Robust loss function scale factor.", 1.0), PARAM(solver_options, solver_options_sptr, "pointer to the nested config options for solver"), PARAM(camera_options, camera_options_sptr, "pointer to the nested config options for camera")) virtual ~optimize_cameras()=default
Destructor.
-
virtual bool check_configuration(vital::config_block_sptr config) const
Check that the algorithm’s currently configuration is valid.
-
virtual void optimize(kwiver::vital::camera_map_sptr &cameras, kwiver::vital::feature_track_set_sptr tracks, kwiver::vital::landmark_map_sptr landmarks, kwiver::vital::sfm_constraints_sptr constraints = nullptr) const
Optimize camera parameters given sets of landmarks and feature tracks
We only optimize cameras that have associating tracks and landmarks in the given maps. The default implementation collects the corresponding features and landmarks for each camera and calls the single camera optimize function.
- Throws:
invalid_value – When one or more of the given pointer is Null.
- Parameters:
cameras – [inout] Cameras to optimize.
tracks – [in] The feature tracks to use as constraints.
landmarks – [in] The landmarks the cameras are viewing.
metadata – [in] The optional metadata to constrain the optimization.
-
virtual void optimize(vital::camera_perspective_sptr &camera, const std::vector<vital::feature_sptr> &features, const std::vector<vital::landmark_sptr> &landmarks, kwiver::vital::sfm_constraints_sptr constraints = nullptr) const
Optimize a single camera given corresponding features and landmarks
This function assumes that 2D features viewed by this camera have already been put into correspondence with 3D landmarks by aligning them into two parallel vectors
- Parameters:
camera – [inout] The camera to optimize.
features – [in] The vector of features observed by
camerato use as constraints.landmarks – [in] The vector of landmarks corresponding to
features.metadata – [in] The optional metadata to constrain the optimization.
-
class priv