48 template<
class GEOMETRY_T>
50 : cameraGeometry_(new camera_geometry_t) {
54 template<
class GEOMETRY_T>
56 std::shared_ptr<const camera_geometry_t> cameraGeometry, uint64_t cameraId,
57 const measurement_t & measurement,
const covariance_t & information) {
58 setCameraId(cameraId);
59 setMeasurement(measurement);
60 setInformation(information);
61 setCameraGeometry(cameraGeometry);
65 template<
class GEOMETRY_T>
67 const covariance_t& information) {
68 information_ = information;
69 covariance_ = information.inverse();
71 Eigen::LLT<Eigen::Matrix2d> lltOfInformation(information_);
72 squareRootInformation_ = lltOfInformation.matrixL().transpose();
76 template<
class GEOMETRY_T>
79 double** jacobians)
const {
81 return EvaluateWithMinimalJacobians(parameters, residuals, jacobians, NULL);
86 template<
class GEOMETRY_T>
88 double const*
const * parameters,
double* residuals,
double** jacobians,
89 double** jacobiansMinimal)
const {
96 Eigen::Map<const Eigen::Vector3d> t_WS_W(¶meters[0][0]);
97 const Eigen::Quaterniond q_WS(parameters[0][6], parameters[0][3],
98 parameters[0][4], parameters[0][5]);
101 Eigen::Map<const Eigen::Vector4d> hp_W(¶meters[1][0]);
105 Eigen::Map<const Eigen::Vector3d> t_SC_S(¶meters[2][0]);
106 const Eigen::Quaterniond q_SC(parameters[2][6], parameters[2][3],
107 parameters[2][4], parameters[2][5]);
110 Eigen::Matrix3d C_SC = q_SC.toRotationMatrix();
111 Eigen::Matrix3d C_CS = C_SC.transpose();
112 Eigen::Matrix4d T_CS = Eigen::Matrix4d::Identity();
113 T_CS.topLeftCorner<3, 3>() = C_CS;
114 T_CS.topRightCorner<3, 1>() = -C_CS * t_SC_S;
115 Eigen::Matrix3d C_WS = q_WS.toRotationMatrix();
116 Eigen::Matrix3d C_SW = C_WS.transpose();
117 Eigen::Matrix4d T_SW = Eigen::Matrix4d::Identity();
118 T_SW.topLeftCorner<3, 3>() = C_SW;
119 T_SW.topRightCorner<3, 1>() = -C_SW * t_WS_W;
120 Eigen::Vector4d hp_S = T_SW * hp_W;
121 Eigen::Vector4d hp_C = T_CS * hp_S;
125 Eigen::Matrix<double, 2, 4> Jh;
126 Eigen::Matrix<double, 2, 4> Jh_weighted;
127 if (jacobians != NULL) {
128 cameraGeometry_->projectHomogeneous(hp_C, &kp, &Jh);
129 Jh_weighted = squareRootInformation_ * Jh;
131 cameraGeometry_->projectHomogeneous(hp_C, &kp);
134 measurement_t error = measurement_ - kp;
137 measurement_t weighted_error = squareRootInformation_ * error;
140 residuals[0] = weighted_error[0];
141 residuals[1] = weighted_error[1];
145 if (fabs(hp_C[3]) > 1.0e-8) {
146 Eigen::Vector3d p_C = hp_C.template head<3>() / hp_C[3];
155 if (jacobians != NULL) {
156 if (jacobians[0] != NULL) {
157 Eigen::Vector3d p = hp_W.head<3>() - t_WS_W * hp_W[3];
158 Eigen::Matrix<double, 4, 6> J;
160 J.topLeftCorner<3, 3>() = C_SW * hp_W[3];
164 Eigen::Matrix<double, 2, 6, Eigen::RowMajor> J0_minimal;
165 J0_minimal = Jh_weighted * T_CS * J;
167 J0_minimal.setZero();
170 Eigen::Matrix<double, 6, 7, Eigen::RowMajor> J_lift;
174 Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor> > J0(
176 J0 = J0_minimal * J_lift;
179 if (jacobiansMinimal != NULL) {
180 if (jacobiansMinimal[0] != NULL) {
181 Eigen::Map<Eigen::Matrix<double, 2, 6, Eigen::RowMajor> > J0_minimal_mapped(
182 jacobiansMinimal[0]);
183 J0_minimal_mapped = J0_minimal;
188 if (jacobians[1] != NULL) {
189 Eigen::Map<Eigen::Matrix<double, 2, 4, Eigen::RowMajor> > J1(
191 Eigen::Matrix4d T_CW = (T_CS * T_SW);
192 J1 = -Jh_weighted * T_CW;
197 if (jacobiansMinimal != NULL) {
198 if (jacobiansMinimal[1] != NULL) {
199 Eigen::Map<Eigen::Matrix<double, 2, 3, Eigen::RowMajor> > J1_minimal_mapped(
200 jacobiansMinimal[1]);
201 Eigen::Matrix<double, 4, 3>
S;
203 S.topLeftCorner<3, 3>().setIdentity();
204 J1_minimal_mapped = J1 * S;
208 if (jacobians[2] != NULL) {
209 Eigen::Vector3d p = hp_S.head<3>() - t_SC_S * hp_S[3];
210 Eigen::Matrix<double, 4, 6> J;
212 J.topLeftCorner<3, 3>() = C_CS * hp_S[3];
216 Eigen::Matrix<double, 2, 6, Eigen::RowMajor> J2_minimal;
217 J2_minimal = Jh_weighted * J;
219 J2_minimal.setZero();
222 Eigen::Matrix<double, 6, 7, Eigen::RowMajor> J_lift;
226 Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor> > J2(
228 J2 = J2_minimal * J_lift;
231 if (jacobiansMinimal != NULL) {
232 if (jacobiansMinimal[2] != NULL) {
233 Eigen::Map<Eigen::Matrix<double, 2, 6, Eigen::RowMajor> > J2_minimal_mapped(
234 jacobiansMinimal[2]);
235 J2_minimal_mapped = J2_minimal;
Eigen::Matrix< Scalar_T, 3, 3 > crossMx(Scalar_T x, Scalar_T y, Scalar_T z)
Cross matrix of a vector [x,y,z]. Adopted from Schweizer-Messer by Paul Furgale.
Definition: operators.hpp:62
virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
This evaluates the error term and additionally computes the Jacobians.
Definition: ReprojectionError.hpp:77
ReprojectionError()
Default constructor.
Definition: ReprojectionError.hpp:49
virtual void setInformation(const covariance_t &information)
Set the information.
Definition: ReprojectionError.hpp:66
static bool liftJacobian(const double *x, double *jacobian)
Computes the Jacobian from minimal space to naively overparameterised space as used by ceres...
Definition: PoseLocalParameterization.cpp:131
virtual bool EvaluateWithMinimalJacobians(double const *const *parameters, double *residuals, double **jacobians, double **jacobiansMinimal) const
This evaluates the error term and additionally computes the Jacobians in the minimal internal represe...
Definition: ReprojectionError.hpp:87
File with some helper functions related to matrix/vector operations.