59 landmark_points.clear();
63 it != observations.end(); ++it)
68 frame_poses[frame_ID] =
CPose3D(0, 0, 0, 0, 0, 0);
69 landmark_points[feat_ID] =
TPoint3D(0, 0, 1);
87 landmark_points.clear();
89 if (observations.empty())
return;
97 it != observations.end(); ++it)
106 frame_poses.assign(max_fr_id + 1,
CPose3D(0, 0, 0, 0, 0, 0));
107 landmark_points.assign(max_pt_id + 1,
TPoint3D(0, 0, 1));
116 template <
bool POSES_INVERSE>
119 std::array<double, 2>& out_residual,
120 const TFramePosesVec::value_type& frame,
121 const TLandmarkLocationsVec::value_type& point,
double&
sum,
122 const bool use_robust_kernel,
const double kernel_param,
123 double* out_kernel_1st_deriv)
126 mrpt::vision::pinhole::projectPoint_no_distortion<POSES_INVERSE>(
127 camera_params, frame, point);
130 out_residual[0] = z_meas.x - z_pred.
x;
131 out_residual[1] = z_meas.y - z_pred.
y;
133 const double sum_2 =
square(out_residual[0]) +
square(out_residual[1]);
135 if (use_robust_kernel)
138 kernel.param_sq =
square(kernel_param);
139 double kernel_1st_deriv, kernel_2nd_deriv;
141 sum += kernel.eval(sum_2, kernel_1st_deriv, kernel_2nd_deriv);
142 if (out_kernel_1st_deriv) *out_kernel_1st_deriv = kernel_1st_deriv;
160 std::vector<std::array<double, 2>>& out_residuals,
161 const bool frame_poses_are_inverse,
const bool use_robust_kernel,
162 const double kernel_param, std::vector<double>* out_kernel_1st_deriv)
168 const size_t N = observations.size();
169 out_residuals.resize(N);
170 if (out_kernel_1st_deriv) out_kernel_1st_deriv->resize(N);
172 for (
size_t i = 0; i < N; i++)
181 ASSERTMSG_(itF != frame_poses.end(),
"Frame ID is not in list!");
182 ASSERTMSG_(itP != landmark_points.end(),
"Landmark ID is not in list!");
184 const TFramePosesMap::mapped_type& frame = itF->second;
185 const TLandmarkLocationsMap::mapped_type& point = itP->second;
187 double* ptr_1st_deriv =
188 out_kernel_1st_deriv ? &((*out_kernel_1st_deriv)[i]) :
nullptr;
190 if (frame_poses_are_inverse)
191 reprojectionResidualsElement<true>(
192 camera_params, OBS, out_residuals[i], frame, point,
sum,
193 use_robust_kernel, kernel_param, ptr_1st_deriv);
195 reprojectionResidualsElement<false>(
196 camera_params, OBS, out_residuals[i], frame, point,
sum,
197 use_robust_kernel, kernel_param, ptr_1st_deriv);
209 std::vector<std::array<double, 2>>& out_residuals,
210 const bool frame_poses_are_inverse,
const bool use_robust_kernel,
211 const double kernel_param, std::vector<double>* out_kernel_1st_deriv)
217 const size_t N = observations.size();
218 out_residuals.resize(N);
219 if (out_kernel_1st_deriv) out_kernel_1st_deriv->resize(N);
221 for (
size_t i = 0; i < N; i++)
230 const TFramePosesVec::value_type& frame = frame_poses[i_f];
231 const TLandmarkLocationsVec::value_type& point = landmark_points[i_p];
233 double* ptr_1st_deriv =
234 out_kernel_1st_deriv ? &((*out_kernel_1st_deriv)[i]) :
nullptr;
236 if (frame_poses_are_inverse)
237 reprojectionResidualsElement<true>(
238 camera_params, OBS, out_residuals[i], frame, point,
sum,
239 use_robust_kernel, kernel_param, ptr_1st_deriv);
241 reprojectionResidualsElement<false>(
242 camera_params, OBS, out_residuals[i], frame, point,
sum,
243 use_robust_kernel, kernel_param, ptr_1st_deriv);
253 const vector<std::array<double, 2>>& residual_vec,
259 const size_t num_fix_frames,
const size_t num_fix_points,
260 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++)
274 const Eigen::Matrix<double, 2, 1> RESID(&residual_vec[i][0]);
278 if (i_f >= num_fix_frames)
280 const size_t frame_id = i_f - num_fix_frames;
284 JtJ.multiply_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 eps_frame[frame_id] += eps_delta * rho_1st_der;
300 if (i_p >= num_fix_points)
302 const size_t point_id = i_p - num_fix_points;
306 JtJ.multiply_AtA(JACOB.
J_point);
311 if (!use_robust_kernel)
313 eps_point[point_id] += eps_delta;
317 const double rho_1st_der = (*kernel_1st_deriv)[i];
318 eps_point[point_id] += eps_delta * rho_1st_der;
330 const size_t delta_first_idx,
const size_t delta_num_vals,
335 new_frame_poses.resize(frame_poses.size());
337 for (
size_t i = 0; i < num_fix_frames; ++i)
338 new_frame_poses[i] = frame_poses[i];
340 size_t delta_used_vals = 0;
341 const double* delta_val = &delta[delta_first_idx];
343 for (
size_t i = num_fix_frames; i < frame_poses.size(); i++)
345 const CPose3D& old_pose = frame_poses[i];
346 CPose3D& new_pose = new_frame_poses[i];
350 const CPose3D incrPose = CPose3D::exp(incr);
358 delta_used_vals += 6;
361 ASSERT_(delta_used_vals == delta_num_vals);
366 const size_t delta_first_idx,
const size_t delta_num_vals,
371 new_landmark_points.resize(landmark_points.size());
373 for (
size_t i = 0; i < num_fix_points; ++i)
374 new_landmark_points[i] = landmark_points[i];
376 size_t delta_used_vals = 0;
377 const double* delta_val = &delta[delta_first_idx];
379 for (
size_t i = num_fix_points; i < landmark_points.size(); i++)
381 const TPoint3D& old_point = landmark_points[i];
382 TPoint3D& new_point = new_landmark_points[i];
384 for (
size_t j = 0; j < 3; j++)
385 new_point[j] = old_point[j] + delta_val[j];
389 delta_used_vals += 3;
392 ASSERT_(delta_used_vals == delta_num_vals);
mrpt::math::CMatrixFixedNumeric< double, ObsDim, PointDof > J_point
TLandmarkID id_feature
A unique ID of this feature.
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.
#define ASSERT_BELOW_(__A, __B)
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
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:
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
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.
A numeric matrix of compile-time fixed size.
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.
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).
void ba_build_gradient_Hessians(const TSequenceFeatureObservations &observations, const std::vector< std::array< double, 2 >> &residual_vec, const mrpt::aligned_std_vector< JacData< 6, 3, 2 >> &jac_data_vec, mrpt::aligned_std_vector< mrpt::math::CMatrixFixedNumeric< double, 6, 6 >> &U, mrpt::aligned_std_vector< CArrayDouble< 6 >> &eps_frame, mrpt::aligned_std_vector< mrpt::math::CMatrixFixedNumeric< double, 3, 3 >> &V, mrpt::aligned_std_vector< CArrayDouble< 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.
#define ASSERTDEB_(f)
Defines an assertion mechanism - only when compiled in debug.
mrpt::aligned_std_vector< mrpt::poses::CPose3D > TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs...
mrpt::math::CMatrixFixedNumeric< double, ObsDim, FrameDof > J_frame
TCameraPoseID id_frame
A unique ID of a "frame" (camera position) from where the feature was observed.
mrpt::aligned_std_map< TCameraPoseID, mrpt::poses::CPose3D > TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
const Scalar * const_iterator
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.