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



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST