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< mrpt::utils::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::math::CVectorDouble &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::math::CVectorDouble &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< mrpt::utils::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 mrpt::vision::add_3d_deltas_to_points | ( | const mrpt::vision::TLandmarkLocationsVec & | landmark_points, |
const mrpt::math::CVectorDouble & | 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" |
Definition at line 354 of file ba_common.cpp.
References ASSERT_, MRPT_END, and MRPT_START.
Referenced by mrpt::vision::bundle_adj_full().
void mrpt::vision::add_se3_deltas_to_frames | ( | const mrpt::vision::TFramePosesVec & | frame_poses, |
const mrpt::math::CVectorDouble & | 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" |
Definition at line 314 of file ba_common.cpp.
References ASSERT_, mrpt::poses::CPose3D::composeFrom(), MRPT_END, and MRPT_START.
Referenced by mrpt::vision::bundle_adj_full().
void 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.
Definition at line 58 of file ba_common.cpp.
References mrpt::utils::keep_max(), MRPT_END, MRPT_START, and MRPT_UNUSED_PARAM.
void 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.
Definition at line 31 of file ba_common.cpp.
References MRPT_END, MRPT_START, and MRPT_UNUSED_PARAM.
double 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. |
Definition at line 51 of file ba_full.cpp.
References mrpt::vision::add_3d_deltas_to_points(), mrpt::vision::add_se3_deltas_to_frames(), ASSERT_, ASSERT_ABOVE_, ASSERT_ABOVEEQ_, mrpt::vision::ba_build_gradient_Hessians(), mrpt::math::CSparseMatrix::compressFromTriplet(), mrpt::utils::CTimeLogger::enter(), eps, mrpt::utils::TParameters< T >::getWithDefaultVal(), mrpt::math::CSparseMatrix::insert_submatrix(), INV_POSES_BOOL, mrpt::pbmap::inverse(), mrpt::utils::keep_max(), mrpt::utils::CTimeLogger::leave(), mrpt::system::os::memcpy(), MRPT_CHECK_NORMAL_NUMBER, MRPT_END, MRPT_START, norm_inf(), mrpt::vision::reprojectionResiduals(), mrpt::math::UNINITIALIZED_MATRIX, and VERBOSE_COUT.
double 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< mrpt::utils::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 instead of , for each F in frame_poses. |
Definition at line 188 of file ba_common.cpp.
References ASSERT_BELOW_, mrpt::vision::TFeatureObservation::id_feature, mrpt::vision::TFeatureObservation::id_frame, MRPT_END, MRPT_START, and mrpt::math::sum().
Referenced by mrpt::vision::bundle_adj_full().
double 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< mrpt::utils::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.
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 140 of file ba_common.cpp.
References ASSERTMSG_, mrpt::vision::TFeatureObservation::id_feature, mrpt::vision::TFeatureObservation::id_frame, MRPT_END, MRPT_START, and mrpt::math::sum().
Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |