Ceres¶
Bundle Adjust Algorithm¶
-
class
bundle_adjust
: public kwiver::vital::algorithm_impl<bundle_adjust, vital::algo::bundle_adjust>¶ A class for bundle adjustment of feature tracks using Ceres.
Public Functions
-
bundle_adjust
()¶ Constructor.
-
~bundle_adjust
()¶ Destructor.
-
config_block_sptr
get_configuration
() const¶ Get this algorithm’s configuration block .
-
void
set_configuration
(vital::config_block_sptr config)¶ Set this algorithm’s properties via a config block.
-
bool
check_configuration
(vital::config_block_sptr config) const¶ Check that the algorithm’s currently configuration is valid.
-
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 feature tracks.
Optimize the camera and landmark parameters given a set of tracks.
- Parameters
[inout] cameras
: the cameras to optimize[inout] landmarks
: the landmarks to optimize[in] tracks
: the feature tracks to use as constraints[in] metadata
: the frame metadata to use as constraints
-
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
[inout] cameras
: the cameras to optimize[inout] landmarks
: the landmarks to optimize[in] tracks
: the feature tracks to use as constraints[in] fixed_cameras
: frame ids for cameras to be fixed in the optimization[in] fixed_landmarks
: landmark ids for landmarks to be fixed in the optimization[in] metadata
: the frame metadata to use as constraints
-
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 Algorithm¶
-
class
optimize_cameras
: public kwiver::vital::algorithm_impl<optimize_cameras, vital::algo::optimize_cameras>¶ A class for optimization of camera paramters using Ceres.
Public Functions
-
optimize_cameras
()¶ Constructor.
-
~optimize_cameras
()¶ Destructor.
-
config_block_sptr
get_configuration
() const¶ Get this algorithm’s configuration block .
-
void
set_configuration
(vital::config_block_sptr config)¶ Set this algorithm’s properties via a config block.
-
bool
check_configuration
(vital::config_block_sptr config) const¶ Check that the algorithm’s currently configuration is valid.
-
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.
- Exceptions
invalid_value
: When one or more of the given pointer is Null.
- Parameters
[inout] cameras
: Cameras to optimize.[in] tracks
: The feature tracks to use as constraints.[in] landmarks
: The landmarks the cameras are viewing.[in] metadata
: The optional metadata to constrain the optimization.
-
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
[inout] camera
: The camera to optimize.[in] features
: The vector of features observed bycamera
to use as constraints.[in] landmarks
: The vector of landmarks corresponding tofeatures
.[in] metadata
: The optional metadata to constrain the optimization.
-
Camera Position Smoothness Class¶
-
class
camera_position_smoothness
¶ Ceres camera smoothness functor.
Public Functions
-
camera_position_smoothness
(const double smoothness)¶ Constructor.
-
template<typename
T
>
booloperator()
(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
[in] prev_pos
: Camera pose data block at previous time[in] curr_pos
: Camera pose data block at current time[in] next_pos
: Camera pose data block at next time[out] residuals
: 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
-
ceres::CostFunction *
create
(const double s)¶ Cost function factory.
-
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
-
camera_limit_forward_motion
(const double scale)¶ Constructor.
-
template<typename
T
>
booloperator()
(const T *const pose1, const T *const pose2, T *residuals) const¶ Camera forward motion error functor for use in Ceres.
- Parameters
[in] pose1
: Camera pose data block at time 1[in] pose2
: Camera pose data block at time 2[out] residuals
: 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
-
ceres::CostFunction *
create
(const double s)¶ Cost function factory.
-
Distortion Poly Radial Class¶
-
class
distortion_poly_radial
¶ Class to hold to distortion function and traits.
Public Static Functions
-
template<typename
T
>
static voidapply
(const T *dist_coeffs, const T *source_xy, T *distorted_xy)¶ Function to apply polynomial radial distortion.
- Parameters
[in] dist_coeffs
: radial distortion coefficients (2)[in] source_xy
: 2D point in normalized image coordinates[out] distorted_xy
: 2D point in distorted normalized image coordinates
-
template<typename
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 voidapply
(const T *dist_coeffs, const T *source_xy, T *distorted_xy)¶ Function to apply polynomial radial and tangential distortion.
- Parameters
[in] dist_coeffs
: radial (3) and tangential (2) distortion coefficients[in] source_xy
: 2D point in normalized image coordinates[out] distorted_xy
: 2D point in distorted normalized image coordinates
-
template<typename
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 voidapply
(const T *dist_coeffs, const T *source_xy, T *distorted_xy)¶ Function to apply rational polynomial radial and tangential distortion.
- Parameters
[in] dist_coeffs
: radial (6) and tangential (2) distortion coefficients[in] source_xy
: 2D point in normalized image coordinates[out] distorted_xy
: 2D point in distorted normalized image coordinates
-
template<typename