Ceres
Bundle Adjust Algorithm
-
class bundle_adjust : public kwiver::vital::algo::bundle_adjust
A class for bundle adjustment of feature tracks using Ceres.
Public Functions
-
bundle_adjust()
Constructor.
-
virtual ~bundle_adjust()
Destructor.
-
virtual vital::config_block_sptr get_configuration() const
Get this algorithm’s configuration block
-
virtual void set_configuration(vital::config_block_sptr config)
Set this algorithm’s properties via a config block.
-
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.
-
bundle_adjust()
Optimize Cameras Algorithm
-
class optimize_cameras : public kwiver::vital::algo::optimize_cameras
A class for optimization of camera paramters using Ceres.
Public Functions
-
optimize_cameras()
Constructor.
-
virtual ~optimize_cameras()
Destructor.
-
virtual vital::config_block_sptr get_configuration() const
Get this algorithm’s configuration block .
-
virtual void set_configuration(vital::config_block_sptr config)
Set this algorithm’s properties via a config block.
-
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
camera
to use as constraints.landmarks – [in] The vector of landmarks corresponding to
features
.metadata – [in] The optional metadata to constrain the optimization.
-
class priv : public kwiver::arrows::ceres::solver_options, public kwiver::arrows::ceres::camera_options
-
optimize_cameras()
Camera Position Smoothness Class
-
class camera_position_smoothness
Ceres camera smoothness functor.
Public Functions
-
inline camera_position_smoothness(const double smoothness, const double fraction = 0.5)
Constructor.
-
template<typename T>
inline bool operator()(const T *const prev_pose, const T *const curr_pose, const T *const next_pose, T *residuals) const Position smoothness error functor for use in Ceres
- Parameters:
prev_pos – [in] Camera pose data block at previous time
curr_pos – [in] Camera pose data block at current time
next_pos – [in] Camera pose data block at next time
residuals – [out] Camera pose blocks contain 6 parameters: 3 for rotation(angle axis), 3 for center Only the camera centers are used in this function to penalize the difference between current position and the average between previous and next positions.
Public Static Functions
-
static inline ::ceres::CostFunction *create(const double s, const double f = 0.5)
Cost function factory.
-
inline camera_position_smoothness(const double smoothness, const double fraction = 0.5)
Camera Limit Forward Motion Class
-
class camera_limit_forward_motion
Ceres camera limit forward motion functor
This class is to reglarize camera motion to minimize the amount of motion in the camera looking direction. This is useful with zoom lenses at long focal lengths where distance and zoom are ambiguous. Adding this constraint allows the optimization to prefer fast zoom changes over fast position change.
Public Functions
-
inline camera_limit_forward_motion(const double scale)
Constructor.
-
template<typename T>
inline bool operator()(const T *const pose1, const T *const pose2, T *residuals) const Camera forward motion error functor for use in Ceres
- Parameters:
pose1 – [in] Camera pose data block at time 1
pose2 – [in] Camera pose data block at time 2
residuals – [out] Camera pose blocks contain 6 parameters: 3 for rotation(angle axis), 3 for center
Public Members
-
double scale_
the magnitude of this constraint
Public Static Functions
-
static inline ::ceres::CostFunction *create(const double s)
Cost function factory.
-
inline camera_limit_forward_motion(const double scale)
Distortion Poly Radial Class
-
class distortion_poly_radial
Class to hold to distortion function and traits.
Public Static Functions
-
template<typename T>
static inline void apply(const T *dist_coeffs, const T *source_xy, T *distorted_xy) Function to apply polynomial radial distortion
- Parameters:
dist_coeffs – [in] radial distortion coefficients (2)
source_xy – [in] 2D point in normalized image coordinates
distorted_xy – [out] 2D point in distorted normalized image coordinates
-
template<typename T>
Distortion Poly Radial Tangential Class
-
class distortion_poly_radial_tangential
Class to hold to distortion function and traits.
Public Static Functions
-
template<typename T>
static inline void apply(const T *dist_coeffs, const T *source_xy, T *distorted_xy) Function to apply polynomial radial and tangential distortion
- Parameters:
dist_coeffs – [in] radial (3) and tangential (2) distortion coefficients
source_xy – [in] 2D point in normalized image coordinates
distorted_xy – [out] 2D point in distorted normalized image coordinates
-
template<typename T>
Distortion Ratpoly Radial Tangential Class
-
class distortion_ratpoly_radial_tangential
Class to hold to distortion function and traits.
Public Static Functions
-
template<typename T>
static inline void apply(const T *dist_coeffs, const T *source_xy, T *distorted_xy) Function to apply rational polynomial radial and tangential distortion
- Parameters:
dist_coeffs – [in] radial (6) and tangential (2) distortion coefficients
source_xy – [in] 2D point in normalized image coordinates
distorted_xy – [out] 2D point in distorted normalized image coordinates
-
template<typename T>
Create Cost Func Factory
-
::ceres::CostFunction *kwiver::arrows::ceres::create_cost_func(mvg::LensDistortionType ldt, double x, double y)
Factory to create Ceres cost functions for each lens distortion type.