60 landmark_points.clear();
63 for (TSequenceFeatureObservations::const_iterator it = observations.begin();
64 it != observations.end(); ++it)
69 frame_poses[frame_ID] =
CPose3D(0, 0, 0, 0, 0, 0);
70 landmark_points[feat_ID] =
TPoint3D(0, 0, 1);
88 landmark_points.clear();
90 if (observations.empty())
return;
97 for (TSequenceFeatureObservations::const_iterator it = observations.begin();
98 it != observations.end(); ++it)
107 frame_poses.assign(max_fr_id + 1,
CPose3D(0, 0, 0, 0, 0, 0));
108 landmark_points.assign(max_pt_id + 1,
TPoint3D(0, 0, 1));
117 template <
bool POSES_INVERSE>
120 std::array<double, 2>& out_residual,
121 const TFramePosesVec::value_type& frame,
122 const TLandmarkLocationsVec::value_type& point,
double&
sum,
123 const bool use_robust_kernel,
const double kernel_param,
124 double* out_kernel_1st_deriv)
127 mrpt::vision::pinhole::projectPoint_no_distortion<POSES_INVERSE>(
128 camera_params, frame, point);
131 out_residual[0] = z_meas.x - z_pred.
x;
132 out_residual[1] = z_meas.y - z_pred.
y;
134 const double sum_2 =
square(out_residual[0]) +
square(out_residual[1]);
136 if (use_robust_kernel)
139 kernel.param_sq =
square(kernel_param);
140 double kernel_1st_deriv, kernel_2nd_deriv;
142 sum += kernel.eval(sum_2, kernel_1st_deriv, kernel_2nd_deriv);
143 if (out_kernel_1st_deriv) *out_kernel_1st_deriv = kernel_1st_deriv;
161 std::vector<std::array<double, 2>>& out_residuals,
162 const bool frame_poses_are_inverse,
const bool use_robust_kernel,
163 const double kernel_param, std::vector<double>* out_kernel_1st_deriv)
169 const size_t N = observations.size();
170 out_residuals.resize(N);
171 if (out_kernel_1st_deriv) out_kernel_1st_deriv->resize(N);
173 for (
size_t i = 0; i < N; i++)
180 TFramePosesMap::const_iterator itF = frame_poses.find(i_f);
181 TLandmarkLocationsMap::const_iterator itP = landmark_points.find(i_p);
182 ASSERTMSG_(itF != frame_poses.end(),
"Frame ID is not in list!");
183 ASSERTMSG_(itP != landmark_points.end(),
"Landmark ID is not in list!");
185 const TFramePosesMap::mapped_type& frame = itF->second;
186 const TLandmarkLocationsMap::mapped_type& point = itP->second;
188 double* ptr_1st_deriv =
189 out_kernel_1st_deriv ? &((*out_kernel_1st_deriv)[i]) :
nullptr;
191 if (frame_poses_are_inverse)
192 reprojectionResidualsElement<true>(
193 camera_params, OBS, out_residuals[i], frame, point,
sum,
194 use_robust_kernel, kernel_param, ptr_1st_deriv);
196 reprojectionResidualsElement<false>(
197 camera_params, OBS, out_residuals[i], frame, point,
sum,
198 use_robust_kernel, kernel_param, ptr_1st_deriv);
210 std::vector<std::array<double, 2>>& out_residuals,
211 const bool frame_poses_are_inverse,
const bool use_robust_kernel,
212 const double kernel_param, std::vector<double>* out_kernel_1st_deriv)
218 const size_t N = observations.size();
219 out_residuals.resize(N);
220 if (out_kernel_1st_deriv) out_kernel_1st_deriv->resize(N);
222 for (
size_t i = 0; i < N; i++)
231 const TFramePosesVec::value_type& frame = frame_poses[i_f];
232 const TLandmarkLocationsVec::value_type& point = landmark_points[i_p];
234 double* ptr_1st_deriv =
235 out_kernel_1st_deriv ? &((*out_kernel_1st_deriv)[i]) :
nullptr;
237 if (frame_poses_are_inverse)
238 reprojectionResidualsElement<true>(
239 camera_params, OBS, out_residuals[i], frame, point,
sum,
240 use_robust_kernel, kernel_param, ptr_1st_deriv);
242 reprojectionResidualsElement<false>(
243 camera_params, OBS, out_residuals[i], frame, point,
sum,
244 use_robust_kernel, kernel_param, ptr_1st_deriv);
254 const vector<std::array<double, 2>>& residual_vec,
260 const size_t num_fix_points,
const vector<double>* kernel_1st_deriv)
264 const size_t N = observations.size();
265 const bool use_robust_kernel = (kernel_1st_deriv !=
nullptr);
267 for (
size_t i = 0; i < N; i++)
278 if (i_f >= num_fix_frames)
280 const size_t frame_id = i_f - num_fix_frames;
284 JtJ.matProductOf_AtA(JACOB.
J_frame);
289 if (!use_robust_kernel)
291 eps_frame[frame_id] += eps_delta;
295 const double rho_1st_der = (*kernel_1st_deriv)[i];
296 auto scaled_eps = eps_delta;
297 scaled_eps *= rho_1st_der;
298 eps_frame[frame_id] += scaled_eps;
302 if (i_p >= num_fix_points)
304 const size_t point_id = i_p - num_fix_points;
308 JtJ.matProductOf_AtA(JACOB.
J_point);
313 if (!use_robust_kernel)
315 eps_point[point_id] += eps_delta;
319 const double rho_1st_der = (*kernel_1st_deriv)[i];
320 auto scaled_eps = eps_delta;
321 scaled_eps *= rho_1st_der;
322 eps_point[point_id] += scaled_eps;
334 const size_t delta_first_idx,
const size_t delta_num_vals,
339 new_frame_poses.resize(frame_poses.size());
341 for (
size_t i = 0; i < num_fix_frames; ++i)
342 new_frame_poses[i] = frame_poses[i];
344 size_t delta_used_vals = 0;
345 const double* delta_val = &delta[delta_first_idx];
347 for (
size_t i = num_fix_frames; i < frame_poses.size(); i++)
349 const CPose3D& old_pose = frame_poses[i];
350 CPose3D& new_pose = new_frame_poses[i];
362 delta_used_vals += 6;
365 ASSERT_(delta_used_vals == delta_num_vals);
370 const size_t delta_first_idx,
const size_t delta_num_vals,
375 new_landmark_points.resize(landmark_points.size());
377 for (
size_t i = 0; i < num_fix_points; ++i)
378 new_landmark_points[i] = landmark_points[i];
380 size_t delta_used_vals = 0;
381 const double* delta_val = &delta[delta_first_idx];
383 for (
size_t i = num_fix_points; i < landmark_points.size(); i++)
385 const TPoint3D& old_point = landmark_points[i];
386 TPoint3D& new_point = new_landmark_points[i];
388 for (
size_t j = 0; j < 3; j++)
389 new_point[j] = old_point[j] + delta_val[j];
393 delta_used_vals += 3;
396 ASSERT_(delta_used_vals == delta_num_vals);
TLandmarkID id_feature
A unique ID of this feature.
A compile-time fixed-size numeric matrix container.
void reprojectionResidualsElement(const TCamera &camera_params, const TFeatureObservation &OBS, std::array< double, 2 > &out_residual, const TFramePosesVec::value_type &frame, const TLandmarkLocationsVec::value_type &point, double &sum, const bool use_robust_kernel, const double kernel_param, double *out_kernel_1st_deriv)
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
uint64_t TFeatureID
Definition of a feature ID.
mrpt::math::CMatrixFixed< double, ObsDim, PointDof > J_point
#define ASSERT_BELOW_(__A, __B)
One feature observation entry, used within sequences with TSequenceFeatureObservations.
A pair (x,y) of pixel coordinates (subpixel resolution).
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...
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:
A complete sequence of observations of features from different camera frames (poses).
T square(const T x)
Inline function for the square of a number.
#define ASSERT_(f)
Defines an assertion mechanism.
std::vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
This base provides a set of functions for maths stuff.
void keep_max(T &var, const K test_val)
If the second argument is above the first one, set the first argument to this higher value...
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
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:
std::map< TLandmarkID, mrpt::math::TPoint3D > TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
CONTAINER::Scalar sum(const CONTAINER &v)
Computes the sum of all the elements.
Classes for computer vision, detectors, features, etc.
Structure to hold the parameters of a pinhole camera model.
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
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...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
mrpt::img::TPixelCoordf px
The pixel coordinates of the observed feature.
Traits for SE(n), rigid-body transformations in R^n space.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
std::map< TCameraPoseID, mrpt::poses::CPose3D > TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
void ba_build_gradient_Hessians(const TSequenceFeatureObservations &observations, const std::vector< std::array< double, 2 >> &residual_vec, const std::vector< JacData< 6, 3, 2 >> &jac_data_vec, std::vector< mrpt::math::CMatrixFixed< double, 6, 6 >> &U, std::vector< CVectorFixedDouble< 6 >> &eps_frame, std::vector< mrpt::math::CMatrixFixed< double, 3, 3 >> &V, std::vector< CVectorFixedDouble< 3 >> &eps_point, const size_t num_fix_frames, const size_t num_fix_points, const vector< double > *kernel_1st_deriv)
Construct the BA linear system.
mrpt::math::CMatrixFixed< double, ObsDim, FrameDof > J_frame
TCameraPoseID id_frame
A unique ID of a "frame" (camera position) from where the feature was observed.
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.