Main MRPT website > C++ reference for MRPT 1.9.9
bundle_adjustment.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #ifndef mrpt_vision_ba_H
11 #define mrpt_vision_ba_H
12 
13 #include <mrpt/vision/types.h>
14 #include <mrpt/utils/TCamera.h>
15 #include <mrpt/utils/TParameters.h>
17 
18 #include <array>
19 #include <functional>
20 
21 // The methods declared in this file are implemented in separate files in:
22 // vision/src/ba_*.cpp
23 namespace mrpt
24 {
25 namespace vision
26 {
27 /** \defgroup bundle_adj Bundle-Adjustment methods
28  * \ingroup mrpt_vision_grp
29  */
30 
31 /** @name Bundle-Adjustment methods
32  @{ */
33 
34 /** A functor type for BA methods \sa bundle_adj_full */
35 using TBundleAdjustmentFeedbackFunctor = std::function<void(
36  const size_t cur_iter, const double cur_total_sq_error,
37  const size_t max_iters,
38  const mrpt::vision::TSequenceFeatureObservations& input_observations,
39  const mrpt::vision::TFramePosesVec& current_frame_estimate,
40  const mrpt::vision::TLandmarkLocationsVec& current_landmark_estimate)>;
41 
42 /** Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the
43  *camera frames & the landmark locations.
44  * At input a gross estimation of the frame poses & the landmark points must be
45  *supplied. If you don't have such a
46  * starting point, use mrpt::vision::ba_initial_estimate() to compute it.
47  *
48  * At output the best found solution will be returned in the variables.
49  *Optionally, a functor can be passed for having
50  * feedback on the progress at each iteration (you can use it to refresh a
51  *GUI, display a progress bar, etc...).
52  *
53  * This implementation is almost entirely an adapted version from RobotVision
54  *(at OpenSLAM.org) (C) by Hauke Strasdat (Imperial College London), licensed
55  *under GNU LGPL.
56  * See the related paper: H. Strasdat, J.M.M. Montiel, A.J. Davison: "Scale
57  *Drift-Aware Large Scale Monocular SLAM", RSS2010,
58  *http://www.roboticsproceedings.org/rss06/p10.html
59  *
60  * List of optional parameters in "extra_params":
61  * - "verbose" : Verbose output (default=0)
62  * - "max_iterations": Maximum number of iterations to run (default=50)
63  * - "robust_kernel": If !=0, use a robust kernel against outliers
64  *(default=1)
65  * - "kernel_param": The pseudo-huber kernel parameter (default=3)
66  * - "mu": Initial mu for LevMarq (default=-1 -> autoguess)
67  * - "num_fix_frames": Number of first frame poses to don't optimize (keep
68  *unmodified as they come in) (default=1: the first pose is the reference and
69  *is not modified)
70  * - "num_fix_points": Idem, for the landmarks positions (default=0:
71  *optimize
72  *all)
73  * - "profiler": If !=0, displays profiling information to the console at
74  *return.
75  *
76  * \note In this function, all coordinates are absolute. Camera frames are such
77  *that +Z points forward from the focal point (see the figure in
78  *mrpt::obs::CObservationImage).
79  * \note The first frame pose will be not updated since at least one frame must
80  *remain fixed.
81  *
82  * \param observations [IN] All the feature observations (WITHOUT distortion),
83  *indexed by feature ID as lists of <frame_ID, (x,y)>. See
84  *TSequenceFeatureObservations.
85  * \param camera_params [IN] The camera parameters, mainly used for the
86  *intrinsic 3x3 matrix. Distortion params are ignored since it's assumed that
87  *\a observations are already undistorted pixels.
88  * \param frame_poses [IN/OUT] Input: Gross estimation of each frame poses.
89  *Output: The found optimal solution.
90  * \param landmark_points [IN/OUT] Input: Gross estimation of each landmark
91  *point. Output: The found optimal solution.
92  * \param extra_params [IN] Optional extra parameters. Read above.
93  * \param user_feedback [IN] If provided, this functor will be called at each
94  *iteration to provide a feedback to the user.
95  *
96  * \return The final overall squared error.
97  * \ingroup bundle_adj
98  */
99 double bundle_adj_full(
100  const mrpt::vision::TSequenceFeatureObservations& observations,
101  const mrpt::utils::TCamera& camera_params,
102  mrpt::vision::TFramePosesVec& frame_poses,
103  mrpt::vision::TLandmarkLocationsVec& landmark_points,
104  const mrpt::utils::TParametersDouble& extra_params =
108 
109 /** @} */
110 
111 /** @name Bundle-Adjustment Auxiliary methods
112  @{ */
113 
114 /** Fills the frames & landmark points maps with an initial gross estimate from
115  * the sequence \a observations, so they can be fed to bundle adjustment
116  * methods.
117  * \sa bundle_adj_full
118  * \ingroup bundle_adj
119  */
121  const mrpt::vision::TSequenceFeatureObservations& observations,
122  const mrpt::utils::TCamera& camera_params,
123  mrpt::vision::TFramePosesVec& frame_poses,
124  mrpt::vision::TLandmarkLocationsVec& landmark_points);
125 
126 //! \overload
128  const mrpt::vision::TSequenceFeatureObservations& observations,
129  const mrpt::utils::TCamera& camera_params,
130  mrpt::vision::TFramePosesMap& frame_poses,
131  mrpt::vision::TLandmarkLocationsMap& landmark_points);
132 
133 /** Compute reprojection error vector (used from within Bundle Adjustment
134  * methods, but can be used in general)
135  * See mrpt::vision::bundle_adj_full for a description of most parameters.
136  * \param frame_poses_are_inverse If set to true, global camera poses are \f$
137  * \ominus F \f$ instead of \f$ F \f$, for each F in frame_poses.
138  *
139  * \return Overall squared reprojection error.
140  * \ingroup bundle_adj
141  */
142 double reprojectionResiduals(
143  const mrpt::vision::TSequenceFeatureObservations& observations,
144  const mrpt::utils::TCamera& camera_params,
145  const mrpt::vision::TFramePosesVec& frame_poses,
146  const mrpt::vision::TLandmarkLocationsVec& landmark_points,
147  std::vector<std::array<double, 2>>& out_residuals,
148  const bool frame_poses_are_inverse, const bool use_robust_kernel = true,
149  const double kernel_param = 3.0,
150  std::vector<double>* out_kernel_1st_deriv = nullptr);
151 
152 //! \overload
153 double reprojectionResiduals(
154  const mrpt::vision::TSequenceFeatureObservations& observations,
155  const mrpt::utils::TCamera& camera_params,
156  const mrpt::vision::TFramePosesMap& frame_poses,
157  const mrpt::vision::TLandmarkLocationsMap& landmark_points,
158  std::vector<std::array<double, 2>>& out_residuals,
159  const bool frame_poses_are_inverse, const bool use_robust_kernel = true,
160  const double kernel_param = 3.0,
161  std::vector<double>* out_kernel_1st_deriv = nullptr);
162 
163 /** For each pose in the vector \a frame_poses, adds a "delta" increment to the
164  * manifold, with the "delta" given in the se(3) Lie algebra:
165  *
166  * new_frame_poses[i] = frame_poses[i] [+]
167  * delta[(first_idx+6*i):(first_idx+6*i+5)] , for every pose in \a
168  * frame_poses
169  *
170  * With the left-multiplication convention of the manifold exp(delta)
171  * operator, that is:
172  *
173  * p <-- p [+] delta ==> p <-- exp(delta) * p
174  *
175  * \param delta_num_vals Used just for sanity check, must be equal to
176  * "frame_poses.size() * 6"
177  * \ingroup bundle_adj
178  */
180  const mrpt::vision::TFramePosesVec& frame_poses,
181  const mrpt::math::CVectorDouble& delta, const size_t delta_first_idx,
182  const size_t delta_num_vals, mrpt::vision::TFramePosesVec& new_frame_poses,
183  const size_t num_fix_frames);
184 
185 /** For each pose in the vector \a frame_poses, adds a "delta" increment to the
186  * manifold, with the "delta" given in the se(3) Lie algebra:
187  *
188  * new_landmark_points[i] = landmark_points[i] +
189  * delta[(first_idx+3*i):(first_idx+3*i+2)] , for every pose in \a
190  * landmark_points
191  *
192  * \param delta_num_vals Used just for sanity check, must be equal to
193  * "landmark_points.size() * 3"
194  * \ingroup bundle_adj
195  */
197  const mrpt::vision::TLandmarkLocationsVec& landmark_points,
198  const mrpt::math::CVectorDouble& delta, const size_t delta_first_idx,
199  const size_t delta_num_vals,
200  mrpt::vision::TLandmarkLocationsVec& new_landmark_points,
201  const size_t num_fix_points);
202 
203 /** @} */
204 }
205 }
206 #endif
mrpt::aligned_containers< TCameraPoseID, mrpt::poses::CPose3D >::map_t TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:42
void 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:
Definition: ba_common.cpp:317
A complete sequence of observations of features from different camera frames (poses).
mrpt::aligned_containers< mrpt::poses::CPose3D >::vector_t TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
void 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:
Definition: ba_common.cpp:354
double 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=mrpt::vision::TBundleAdjustmentFeedbackFunctor())
Sparse Levenberg-Marquart solution to bundle adjustment - optimizes all the camera frames & the landm...
Definition: ba_full.cpp:52
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
double 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< std::array< 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=nullptr)
Compute reprojection error vector (used from within Bundle Adjustment methods, but can be used in gen...
Definition: ba_common.cpp:191
typedef void(APIENTRYP PFNGLBLENDCOLORPROC)(GLclampf red
std::map< TLandmarkID, mrpt::math::TPoint3D > TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
std::function< void(const size_t cur_iter, const double cur_total_sq_error, const size_t max_iters, const mrpt::vision::TSequenceFeatureObservations &input_observations, const mrpt::vision::TFramePosesVec &current_frame_estimate, const mrpt::vision::TLandmarkLocationsVec &current_landmark_estimate)> TBundleAdjustmentFeedbackFunctor
A functor type for BA methods.
void 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...
Definition: ba_common.cpp:60
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:32



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019