29 #include <Eigen/Dense> 44 #define VERBOSE_COUT \ 49 template <
int FrameDof,
int Po
intDof,
int ObsDim>
78 template <
bool POSES_ARE_INVERSE>
88 if (POSES_ARE_INVERSE)
90 landmark_global.
x, landmark_global.
y, landmark_global.
z, x, y, z);
93 landmark_global.
x, landmark_global.
y, landmark_global.
z, x, y, z);
96 const double _z = 1.0 / z;
97 const double fx_z = camera_params.
fx() * _z;
98 const double fy_z = camera_params.
fy() * _z;
99 const double _z2 =
square(_z);
100 const double fx_z2 = camera_params.
fx() * _z2;
101 const double fy_z2 = camera_params.
fy() * _z2;
103 if (POSES_ARE_INVERSE)
105 const double xy = x * y;
107 const double J_vals[] = {fx_z,
111 camera_params.
fx() * (1 +
square(x * _z)),
116 -camera_params.
fy() * (1 +
square(y * _z)),
125 const double jac_proj_vals[] = {fx_z, 0, -fx_z2 * x,
126 0, fy_z, -fy_z2 * y};
129 const double p_x = cam_pose.
x();
130 const double p_y = cam_pose.
y();
131 const double p_z = cam_pose.z();
132 const double tx = landmark_global.
x - p_x;
133 const double ty = landmark_global.
y - p_y;
134 const double tz = landmark_global.
z - p_z;
136 const double aux_vals[] = {
140 tz *
R(1, 0) - ty *
R(2, 0) +
R(1, 0) * p_z -
R(2, 0) * p_y,
141 tx *
R(2, 0) - tz *
R(0, 0) -
R(0, 0) * p_z +
R(2, 0) * p_x,
142 ty *
R(0, 0) - tx *
R(1, 0) +
R(0, 0) * p_y -
R(1, 0) * p_x,
146 tz *
R(1, 1) - ty *
R(2, 1) +
R(1, 1) * p_z -
R(2, 1) * p_y,
147 tx *
R(2, 1) - tz *
R(0, 1) -
R(0, 1) * p_z +
R(2, 1) * p_x,
148 ty *
R(0, 1) - tx *
R(1, 1) +
R(0, 1) * p_y -
R(1, 1) * p_x,
152 tz *
R(1, 2) - ty *
R(2, 2) +
R(1, 2) * p_z -
R(2, 2) * p_y,
153 tx *
R(2, 2) - tz *
R(0, 2) -
R(0, 2) * p_z +
R(2, 2) * p_x,
154 ty *
R(0, 2) - tx *
R(1, 2) +
R(0, 2) * p_y -
R(1, 2) * p_x};
156 out_J = jac_proj * vals;
165 template <
bool POSES_ARE_INVERSE>
178 if (POSES_ARE_INVERSE)
180 landmark_global.
x, landmark_global.
y, landmark_global.
z, l.
x, l.
y,
184 landmark_global.
x, landmark_global.
y, landmark_global.
z, l.
x, l.
y,
188 const double _z = 1.0 / l.
z;
189 const double _z2 =
square(_z);
191 const double tmp_vals[] = {
192 camera_params.
fx() * _z, 0,
193 -camera_params.
fx() * l.
x * _z2, 0,
194 camera_params.
fy() * _z, -camera_params.
fy() * l.
y * _z2};
197 out_J = tmp * dp_point;
205 template <
bool POSES_ARE_INVERSE>
211 const size_t num_fix_points)
217 ASSERT_(!frame_poses.empty() && !landmark_points.empty());
218 const size_t N = jac_data_vec.size();
220 for (
size_t i = 0; i < N; i++)
230 if (i_f >= num_fix_frames)
232 frameJac<POSES_ARE_INVERSE>(
233 camera_params, frame_poses[i_f], landmark_points[i_p],
238 if (i_p >= num_fix_points)
240 pointJac<POSES_ARE_INVERSE>(
241 camera_params, frame_poses[i_f], landmark_points[i_p],
254 const std::vector<std::array<double, 2>>& residual_vec,
260 const size_t num_fix_points,
const vector<double>* kernel_1st_deriv);
void frameJac(const mrpt::img::TCamera &camera_params, const mrpt::poses::CPose3D &cam_pose, const mrpt::math::TPoint3D &landmark_global, mrpt::math::CMatrixFixed< double, 2, 6 > &out_J)
The projective camera 2x6 Jacobian (wrt the 6D camera pose)
A compile-time fixed-size numeric matrix container.
uint64_t TCameraPoseID
Unique IDs for camera frames (poses)
uint64_t TLandmarkID
Unique IDs for landmarks.
double fx() const
Get the value of the focal length x-value (in pixels).
mrpt::math::CMatrixFixed< double, ObsDim, PointDof > J_point
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt) const
Computes the 3D point L such as .
double fy() const
Get the value of the focal length y-value (in pixels).
void ba_compute_Jacobians(const TFramePosesVec &frame_poses, const TLandmarkLocationsVec &landmark_points, const mrpt::img::TCamera &camera_params, std::vector< JacData< 6, 3, 2 >> &jac_data_vec, const size_t num_fix_frames, const size_t num_fix_points)
A complete sequence of observations of features from different camera frames (poses).
#define ASSERT_(f)
Defines an assertion mechanism.
void loadFromArray(const VECTOR &vals)
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 pointJac(const mrpt::img::TCamera &camera_params, const mrpt::poses::CPose3D &cam_pose, const mrpt::math::TPoint3D &landmark_global, mrpt::math::CMatrixFixed< double, 2, 3 > &out_J)
Jacobians wrt the point.
Classes for computer vision, detectors, features, etc.
Parameters for the Brown-Conrady camera lens distortion model.
double x() const
Common members of all points & poses classes.
return_t square(const num_t x)
Inline function for the square of a number.
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).
#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.
CVectorFixed< double, N > CVectorFixedDouble
Specialization of CVectorFixed for double numbers.
mrpt::math::CMatrixFixed< double, ObsDim, FrameDof > J_frame
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
std::vector< mrpt::math::TPoint3D > TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.