![]() |
Bundle-Adjustment methods | |
double VISION_IMPEXP | mrpt::vision::bundle_adj_full (const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::utils::TParametersDouble &extra_params=mrpt::utils::TParametersDouble(), const mrpt::vision::TBundleAdjustmentFeedbackFunctor user_feedback=NULL) |
Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landmark locations. More... | |
Bundle-Adjustment Auxiliary methods | |
void VISION_IMPEXP | mrpt::vision::ba_initial_estimate (const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, mrpt::vision::TFramePosesVec &frame_poses, mrpt::vision::TLandmarkLocationsVec &landmark_points) |
Fills the frames & landmark points maps with an initial gross estimate from the sequence observations, so they can be fed to bundle adjustment methods. More... | |
double VISION_IMPEXP | mrpt::vision::reprojectionResiduals (const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::vision::TLandmarkLocationsVec &landmark_points, std::vector< CArray< double, 2 > > &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0, std::vector< double > *out_kernel_1st_deriv=NULL) |
Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in general) See mrpt::vision::bundle_adj_full for a description of most parameters. More... | |
void VISION_IMPEXP | mrpt::vision::add_se3_deltas_to_frames (const mrpt::vision::TFramePosesVec &frame_poses, const mrpt::vector_double &delta, const size_t delta_first_idx, const size_t delta_num_vals, mrpt::vision::TFramePosesVec &new_frame_poses, const size_t num_fix_frames) |
For each pose in the vector frame_poses, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra: More... | |
void VISION_IMPEXP | mrpt::vision::add_3d_deltas_to_points (const mrpt::vision::TLandmarkLocationsVec &landmark_points, const mrpt::vector_double &delta, const size_t delta_first_idx, const size_t delta_num_vals, mrpt::vision::TLandmarkLocationsVec &new_landmark_points, const size_t num_fix_points) |
For each pose in the vector frame_poses, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra: More... | |
void VISION_IMPEXP | mrpt::vision::ba_initial_estimate (const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, mrpt::vision::TFramePosesMap &frame_poses, mrpt::vision::TLandmarkLocationsMap &landmark_points) |
double VISION_IMPEXP | mrpt::vision::reprojectionResiduals (const mrpt::vision::TSequenceFeatureObservations &observations, const mrpt::utils::TCamera &camera_params, const mrpt::vision::TFramePosesMap &frame_poses, const mrpt::vision::TLandmarkLocationsMap &landmark_points, std::vector< CArray< double, 2 > > &out_residuals, const bool frame_poses_are_inverse, const bool use_robust_kernel=true, const double kernel_param=3.0, std::vector< double > *out_kernel_1st_deriv=NULL) |
void VISION_IMPEXP mrpt::vision::add_3d_deltas_to_points | ( | const mrpt::vision::TLandmarkLocationsVec & | landmark_points, |
const mrpt::vector_double & | delta, | ||
const size_t | delta_first_idx, | ||
const size_t | delta_num_vals, | ||
mrpt::vision::TLandmarkLocationsVec & | new_landmark_points, | ||
const size_t | num_fix_points | ||
) |
For each pose in the vector frame_poses, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra:
new_landmark_points[i] = landmark_points[i] + delta[(first_idx+3*i):(first_idx+3*i+2)] , for every pose in landmark_points
delta_num_vals | Used just for sanity check, must be equal to "landmark_points.size() * 3" |
void VISION_IMPEXP mrpt::vision::add_se3_deltas_to_frames | ( | const mrpt::vision::TFramePosesVec & | frame_poses, |
const mrpt::vector_double & | delta, | ||
const size_t | delta_first_idx, | ||
const size_t | delta_num_vals, | ||
mrpt::vision::TFramePosesVec & | new_frame_poses, | ||
const size_t | num_fix_frames | ||
) |
For each pose in the vector frame_poses, adds a "delta" increment to the manifold, with the "delta" given in the se(3) Lie algebra:
new_frame_poses[i] = frame_poses[i] [+] delta[(first_idx+6*i):(first_idx+6*i+5)] , for every pose in frame_poses
With the left-multiplication convention of the manifold exp(delta) operator, that is:
p <– p [+] delta ==> p <– exp(delta) * p
delta_num_vals | Used just for sanity check, must be equal to "frame_poses.size() * 6" |
void VISION_IMPEXP mrpt::vision::ba_initial_estimate | ( | const mrpt::vision::TSequenceFeatureObservations & | observations, |
const mrpt::utils::TCamera & | camera_params, | ||
mrpt::vision::TFramePosesVec & | frame_poses, | ||
mrpt::vision::TLandmarkLocationsVec & | landmark_points | ||
) |
Fills the frames & landmark points maps with an initial gross estimate from the sequence observations, so they can be fed to bundle adjustment methods.
void VISION_IMPEXP mrpt::vision::ba_initial_estimate | ( | const mrpt::vision::TSequenceFeatureObservations & | observations, |
const mrpt::utils::TCamera & | camera_params, | ||
mrpt::vision::TFramePosesMap & | frame_poses, | ||
mrpt::vision::TLandmarkLocationsMap & | landmark_points | ||
) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
double VISION_IMPEXP mrpt::vision::bundle_adj_full | ( | const mrpt::vision::TSequenceFeatureObservations & | observations, |
const mrpt::utils::TCamera & | camera_params, | ||
mrpt::vision::TFramePosesVec & | frame_poses, | ||
mrpt::vision::TLandmarkLocationsVec & | landmark_points, | ||
const mrpt::utils::TParametersDouble & | extra_params = mrpt::utils::TParametersDouble() , |
||
const mrpt::vision::TBundleAdjustmentFeedbackFunctor | user_feedback = NULL |
||
) |
Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landmark locations.
At input a gross estimation of the frame poses & the landmark points must be supplied. If you don't have such a starting point, use mrpt::vision::ba_initial_estimate() to compute it.
At output the best found solution will be returned in the variables. Optionally, a functor can be passed for having feedback on the progress at each iteration (you can use it to refresh a GUI, display a progress bar, etc...).
This implementation is almost entirely an adapted version from RobotVision (at OpenSLAM.org) (C) by Hauke Strasdat (Imperial College London), licensed under GNU LGPL. See the related paper: H. Strasdat, J.M.M. Montiel, A.J. Davison: "Scale Drift-Aware Large Scale Monocular SLAM", RSS2010, http://www.roboticsproceedings.org/rss06/p10.html
List of optional parameters in "extra_params":
observations | [IN] All the feature observations (WITHOUT distortion), indexed by feature ID as lists of <frame_ID, (x,y)>. See TSequenceFeatureObservations. |
camera_params | [IN] The camera parameters, mainly used for the intrinsic 3x3 matrix. Distortion params are ignored since it's assumed that observations are already undistorted pixels. |
frame_poses | [IN/OUT] Input: Gross estimation of each frame poses. Output: The found optimal solution. |
landmark_points | [IN/OUT] Input: Gross estimation of each landmark point. Output: The found optimal solution. |
extra_params | [IN] Optional extra parameters. Read above. |
user_feedback | [IN] If provided, this functor will be called at each iteration to provide a feedback to the user. |
double VISION_IMPEXP mrpt::vision::reprojectionResiduals | ( | const mrpt::vision::TSequenceFeatureObservations & | observations, |
const mrpt::utils::TCamera & | camera_params, | ||
const mrpt::vision::TFramePosesVec & | frame_poses, | ||
const mrpt::vision::TLandmarkLocationsVec & | landmark_points, | ||
std::vector< CArray< double, 2 > > & | out_residuals, | ||
const bool | frame_poses_are_inverse, | ||
const bool | use_robust_kernel = true , |
||
const double | kernel_param = 3.0 , |
||
std::vector< double > * | out_kernel_1st_deriv = NULL |
||
) |
Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in general) See mrpt::vision::bundle_adj_full for a description of most parameters.
frame_poses_are_inverse | If set to true, global camera poses are ![]() ![]() |
double VISION_IMPEXP mrpt::vision::reprojectionResiduals | ( | const mrpt::vision::TSequenceFeatureObservations & | observations, |
const mrpt::utils::TCamera & | camera_params, | ||
const mrpt::vision::TFramePosesMap & | frame_poses, | ||
const mrpt::vision::TLandmarkLocationsMap & | landmark_points, | ||
std::vector< CArray< double, 2 > > & | out_residuals, | ||
const bool | frame_poses_are_inverse, | ||
const bool | use_robust_kernel = true , |
||
const double | kernel_param = 3.0 , |
||
std::vector< double > * | out_kernel_1st_deriv = NULL |
||
) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Page generated by Doxygen 1.8.14 for MRPT 1.0.2 SVN: at lun oct 28 00:52:41 CET 2019 | Hosted on: |