25 #ifndef INCLUDED_ImagePointMeasurement_h_GUID_BE292A08_8C31_4987_E179_CD2F0CE63183
26 #define INCLUDED_ImagePointMeasurement_h_GUID_BE292A08_8C31_4987_E179_CD2F0CE63183
43 using AugmentedStateWithBeacon =
44 kalman::AugmentedState<kalman::pose_externalized_rotation::State,
45 kalman::PureVectorState<3>>;
47 Eigen::Vector2d principalPoint;
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 class ImagePointMeasurement {
56 using Vector = kalman::types::Vector<DIMENSION>;
57 using SquareMatrix = kalman::types::SquareMatrix<DIMENSION>;
58 using State = AugmentedStateWithBeacon;
61 kalman::types::Dimension<State>::value>;
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 explicit ImagePointMeasurement(CameraModel
const &cam)
64 : m_variance(2.0), m_cam(cam) {}
69 m_beacon = state.
b().stateVector();
70 m_rot = state.a().getCombinedQuaternion().toRotationMatrix();
71 m_objExtRot = state.a().getQuaternion() * m_beacon;
72 m_incRot = state.a().incrementalOrientation();
73 m_rotatedObjPoint = m_rot * m_beacon;
74 m_rotatedTranslatedPoint = m_rotatedObjPoint + state.a().position();
75 m_xlate = state.a().position();
77 Vector getResidual(State
const &state)
const {
79 Eigen::Vector2d predicted =
80 projectPoint(m_cam.focalLength, m_cam.principalPoint,
81 m_rotatedTranslatedPoint);
82 return m_measurement - predicted;
85 void setMeasurement(Vector
const &m) { m_measurement = m; }
86 Eigen::Matrix<double, 2, 3> getBeaconJacobian()
const {
87 auto v1 = m_rot(0, 2) * m_beacon[2] + m_rot(0, 1) * m_beacon[1] +
88 m_beacon[0] * m_rot(0, 0) + m_xlate[0];
89 auto v2 = m_beacon[2] * m_rot(2, 2) + m_beacon[1] * m_rot(2, 1) +
90 m_beacon[0] * m_rot(2, 0) + m_xlate[2];
91 auto v3 = 1 / (v2 * v2);
93 auto v5 = m_rot(1, 2) * m_beacon[2] + m_beacon[1] * m_rot(1, 1) +
94 m_beacon[0] * m_rot(1, 0) + m_xlate[1];
95 Eigen::Matrix<double, 2, 3> ret;
96 ret << m_rot(0, 0) * v4 * m_cam.focalLength -
97 v1 * m_rot(2, 0) * v3 * m_cam.focalLength,
98 m_rot(0, 1) * v4 * m_cam.focalLength -
99 v1 * m_rot(2, 1) * v3 * m_cam.focalLength,
100 m_rot(0, 2) * v4 * m_cam.focalLength -
101 v1 * m_rot(2, 2) * v3 * m_cam.focalLength,
102 m_rot(1, 0) * v4 * m_cam.focalLength -
103 v5 * m_rot(2, 0) * v3 * m_cam.focalLength,
104 m_rot(1, 1) * v4 * m_cam.focalLength -
105 v5 * m_rot(2, 1) * v3 * m_cam.focalLength,
106 m_rot(1, 2) * v4 * m_cam.focalLength -
107 v5 * m_rot(2, 2) * v3 * m_cam.focalLength;
111 Eigen::Matrix<double, 2, 3> getRotationJacobian()
const {
113 auto v1 = m_rotatedObjPoint[0] + m_xlate[0];
114 auto v2 = m_rotatedObjPoint[2] + m_xlate[2];
115 auto v3 = 1 / (v2 * v2);
117 auto v5 = m_rotatedObjPoint[1] + m_xlate[1];
118 Eigen::Matrix<double, 2, 3> ret;
119 ret << -v1 * m_rotatedObjPoint[1] * v3 * m_cam.focalLength,
120 m_rotatedObjPoint[2] * v4 * m_cam.focalLength +
121 m_rotatedObjPoint[0] * v1 * v3 * m_cam.focalLength,
122 -m_rotatedObjPoint[1] * v4 * m_cam.focalLength,
123 (-m_rotatedObjPoint[2] * v4 * m_cam.focalLength) -
124 m_rotatedObjPoint[1] * v5 * v3 * m_cam.focalLength,
125 m_rotatedObjPoint[0] * v5 * v3 * m_cam.focalLength,
126 m_rotatedObjPoint[0] * v4 * m_cam.focalLength;
132 Eigen::Matrix<double, 2, 3> getRotationJacobian()
const {
137 Eigen::Array2d rotXlated =
138 m_rotatedTranslatedPoint.head<2>().array();
139 Eigen::Array2d rotObj = m_rotatedObjPoint.head<2>().array();
143 Eigen::Array2d negativePositive(-1, 1);
144 Eigen::Array2d positiveNegative(1, -1);
146 double zRecip = 1. / m_rotatedTranslatedPoint.z();
147 double rotObjZ = m_rotatedObjPoint.z();
148 Eigen::Array2d mainDiagonal =
149 rotXlated * rotObj.reverse() * negativePositive * zRecip;
150 Eigen::Array2d otherDiagonal =
151 (rotObj * rotXlated * zRecip + rotObjZ) * positiveNegative;
152 Eigen::Array2d lastCol = rotObj.reverse() * negativePositive;
153 Eigen::Matrix<double, 2, 3> prelim;
154 prelim.leftCols<2>() << mainDiagonal[0], otherDiagonal[0],
155 otherDiagonal[1], mainDiagonal[1];
156 prelim.rightCols<1>() << lastCol.matrix();
157 return prelim * zRecip * m_cam.focalLength;
162 Eigen::Matrix<double, 2, 3> getRotationJacobian()
const {
167 Eigen::Matrix3d incrotOP;
168 incrotOP.triangularView<Eigen::Upper>() =
169 m_incRot * m_incRot.transpose();
171 auto v1 = 0.5 - incrotOP(1, 2) / 24;
172 auto v2 = 2 * m_incRot[0] * v1;
173 auto v3 = -incrotOP(1, 2) / 6;
174 auto v4 = incrotOP(1, 2) / 6;
175 auto v5 = -(incrotOP(1, 1) * m_incRot[2]) / 24;
177 m_objExtRot[0] * (v5 + v4) + m_objExtRot[1] * (v3 + v2 + 1);
178 auto v7 = -incrotOP(0, 2) / 6;
180 auto v9 = 0.5 - incrotOP(0, 2) / 24;
181 auto v10 = incrotOP(1, 1) * v9;
183 auto v12 = incrotOP(0, 0) * v1;
184 auto v13 = m_objExtRot[0] * (v10 - m_incRot[1] * v8) +
185 m_objExtRot[1] * (v12 + m_incRot[0] * v11) +
186 m_objExtRot[2] + m_xlate[2];
187 auto v14 = 1 / (v13 * v13);
188 auto v15 = -incrotOP(0, 1) / 6;
190 auto v17 = 0.5 - incrotOP(0, 1) / 24;
191 auto v18 = incrotOP(2, 2) * v17;
192 auto v19 = m_objExtRot[2] * (m_incRot[1] * v8 + v10) +
193 m_objExtRot[1] * (v18 - m_incRot[2] * v16) +
194 m_objExtRot[0] + m_xlate[0];
196 auto v21 = -(m_incRot[1] * incrotOP(2, 2)) / 24;
197 auto v22 = 2 * m_incRot[1] * v9;
198 auto v23 = incrotOP(0, 2) / 6;
199 auto v24 = -(m_incRot[0] * incrotOP(2, 2)) / 24;
200 auto v25 = -(incrotOP(0, 0) * m_incRot[2]) / 24;
202 m_objExtRot[1] * (v7 + v25) + m_objExtRot[0] * (v23 + v22 - 1);
203 auto v27 = incrotOP(0, 1) / 6;
204 auto v28 = 2 * m_incRot[2] * v17;
205 auto v29 = -(m_incRot[0] * incrotOP(1, 1)) / 24;
206 auto v30 = -(incrotOP(0, 0) * m_incRot[1]) / 24;
208 m_objExtRot[1] * (v30 + v15) + m_objExtRot[0] * (v29 + v27);
209 auto v32 = m_objExtRot[0] * (v18 + m_incRot[2] * v16) +
210 m_objExtRot[2] * (v12 - m_incRot[0] * v11) +
211 m_objExtRot[1] + m_xlate[1];
212 Eigen::Matrix<double, 2, 3> ret;
213 ret << v20 * (m_objExtRot[1] * (v21 + v4) +
214 (v5 + v3) * m_objExtRot[2]) *
216 v6 * v14 * v19 * m_cam.focalLength,
217 v20 * (m_objExtRot[1] * (v24 + v23) +
218 (v22 + v7 + 1) * m_objExtRot[2]) *
220 v26 * v14 * v19 * m_cam.focalLength,
221 v20 * ((v29 + v15) * m_objExtRot[2] +
222 m_objExtRot[1] * (v28 + v27 - 1)) *
224 v31 * v14 * v19 * m_cam.focalLength,
225 v20 * (m_objExtRot[0] * (v21 + v3) +
226 (v4 + v2 - 1) * m_objExtRot[2]) *
228 v6 * v14 * v32 * m_cam.focalLength,
229 v20 * (m_objExtRot[0] * (v24 + v7) +
230 (v25 + v23) * m_objExtRot[2]) *
232 v26 * v14 * v32 * m_cam.focalLength,
233 v20 * ((v30 + v27) * m_objExtRot[2] +
234 m_objExtRot[0] * (v28 + v15 + 1)) *
236 v31 * v14 * v32 * m_cam.focalLength;
240 Jacobian getJacobian(State
const &state)
const {
244 Eigen::Matrix2d::Identity() *
245 (m_cam.focalLength / m_rotatedTranslatedPoint.z()),
247 -m_rotatedTranslatedPoint.head<2>() * m_cam.focalLength /
248 (m_rotatedTranslatedPoint.z() *
249 m_rotatedTranslatedPoint.z()),
251 getRotationJacobian(),
253 Eigen::Matrix<double, 2, 6>::Zero(),
259 void setVariance(
double s) {
266 return Vector::Constant(m_variance).asDiagonal();
271 Vector m_measurement;
273 Eigen::Vector3d m_beacon;
274 Eigen::Vector3d m_objExtRot;
275 Eigen::Vector3d m_incRot;
276 Eigen::Vector3d m_rotatedObjPoint;
277 Eigen::Vector3d m_rotatedTranslatedPoint;
278 Eigen::Vector3d m_xlate;
279 Eigen::Matrix3d m_rot;
284 #endif // INCLUDED_ImagePointMeasurement_h_GUID_BE292A08_8C31_4987_E179_CD2F0CE63183
void updateFromState(State const &state)
Updates some internal cached partial solutions.
SquareMatrix getCovariance(State &state) const
StateTypeB & b()
Access the second part of the state.
std::size_t DimensionType
Type for dimensions.
Eigen::Matrix< Scalar, m, n > Matrix
A matrix with rows = m, cols = n.