OSVR-Core
ImagePointMeasurement.h
Go to the documentation of this file.
1 
11 // Copyright 2015 Sensics, Inc.
12 //
13 // Licensed under the Apache License, Version 2.0 (the "License");
14 // you may not use this file except in compliance with the License.
15 // You may obtain a copy of the License at
16 //
17 // http://www.apache.org/licenses/LICENSE-2.0
18 //
19 // Unless required by applicable law or agreed to in writing, software
20 // distributed under the License is distributed on an "AS IS" BASIS,
21 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 // See the License for the specific language governing permissions and
23 // limitations under the License.
24 
25 #ifndef INCLUDED_ImagePointMeasurement_h_GUID_BE292A08_8C31_4987_E179_CD2F0CE63183
26 #define INCLUDED_ImagePointMeasurement_h_GUID_BE292A08_8C31_4987_E179_CD2F0CE63183
27 
28 // Internal Includes
29 #include "ProjectPoint.h"
33 #include <osvr/Kalman/PoseState.h>
34 
35 // Library/third-party includes
36 // - none
37 
38 // Standard includes
39 // - none
40 
41 namespace osvr {
42 namespace vbtracker {
43  using AugmentedStateWithBeacon =
44  kalman::AugmentedState<kalman::pose_externalized_rotation::State,
45  kalman::PureVectorState<3>>;
46  struct CameraModel {
47  Eigen::Vector2d principalPoint;
48  double focalLength;
49  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50  };
53  class ImagePointMeasurement {
54  public:
55  static const kalman::types::DimensionType DIMENSION = 2;
56  using Vector = kalman::types::Vector<DIMENSION>;
57  using SquareMatrix = kalman::types::SquareMatrix<DIMENSION>;
58  using State = AugmentedStateWithBeacon;
59  using Jacobian =
60  kalman::types::Matrix<DIMENSION,
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) {}
65 
67  void updateFromState(State const &state) {
68  // 3d position of beacon
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();
76  }
77  Vector getResidual(State const &state) const {
78  // 3d position of beacon
79  Eigen::Vector2d predicted =
80  projectPoint(m_cam.focalLength, m_cam.principalPoint,
81  m_rotatedTranslatedPoint);
82  return m_measurement - predicted;
83  }
84 
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);
92  auto v4 = 1 / 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];
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;
108  return ret;
109  }
110 #if 0
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);
116  auto v4 = 1 / v2;
117  auto v5 = m_rotatedObjPoint[1] + m_xlate[1];
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;
127  return ret;
128  }
129 #endif
130 
131 #if 1
132  Eigen::Matrix<double, 2, 3> getRotationJacobian() const {
135  // just grabbing x and y as an array for component-wise manip right
136  // now.
137  Eigen::Array2d rotXlated =
138  m_rotatedTranslatedPoint.head<2>().array();
139  Eigen::Array2d rotObj = m_rotatedObjPoint.head<2>().array();
140 
141  // Utility because a lot of this requires negatives applied in one
142  // row but not the other.
143  Eigen::Array2d negativePositive(-1, 1);
144  Eigen::Array2d positiveNegative(1, -1);
145  // Some common Z stuff
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;
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;
158  }
159 #endif
160 
161 #if 0
162  Eigen::Matrix<double, 2, 3> getRotationJacobian() const {
167  Eigen::Matrix3d incrotOP;
168  incrotOP.triangularView<Eigen::Upper>() =
169  m_incRot * m_incRot.transpose();
170 
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;
176  auto v6 =
177  m_objExtRot[0] * (v5 + v4) + m_objExtRot[1] * (v3 + v2 + 1);
178  auto v7 = -incrotOP(0, 2) / 6;
179  auto v8 = v7 + 1;
180  auto v9 = 0.5 - incrotOP(0, 2) / 24;
181  auto v10 = incrotOP(1, 1) * v9;
182  auto v11 = v3 + 1;
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;
189  auto v16 = v15 + 1;
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];
195  auto v20 = 1 / v13;
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;
201  auto v26 =
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;
207  auto v31 =
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];
213  ret << v20 * (m_objExtRot[1] * (v21 + v4) +
214  (v5 + v3) * m_objExtRot[2]) *
215  m_cam.focalLength -
216  v6 * v14 * v19 * m_cam.focalLength,
217  v20 * (m_objExtRot[1] * (v24 + v23) +
218  (v22 + v7 + 1) * m_objExtRot[2]) *
219  m_cam.focalLength -
220  v26 * v14 * v19 * m_cam.focalLength,
221  v20 * ((v29 + v15) * m_objExtRot[2] +
222  m_objExtRot[1] * (v28 + v27 - 1)) *
223  m_cam.focalLength -
224  v31 * v14 * v19 * m_cam.focalLength,
225  v20 * (m_objExtRot[0] * (v21 + v3) +
226  (v4 + v2 - 1) * m_objExtRot[2]) *
227  m_cam.focalLength -
228  v6 * v14 * v32 * m_cam.focalLength,
229  v20 * (m_objExtRot[0] * (v24 + v7) +
230  (v25 + v23) * m_objExtRot[2]) *
231  m_cam.focalLength -
232  v26 * v14 * v32 * m_cam.focalLength,
233  v20 * ((v30 + v27) * m_objExtRot[2] +
234  m_objExtRot[0] * (v28 + v15 + 1)) *
235  m_cam.focalLength -
236  v31 * v14 * v32 * m_cam.focalLength;
237  return ret;
238  }
239 #endif
240  Jacobian getJacobian(State const &state) const {
241  Jacobian ret;
242  ret <<
243  // with respect to change in x or y
244  Eigen::Matrix2d::Identity() *
245  (m_cam.focalLength / m_rotatedTranslatedPoint.z()),
246  // with respect to change in z
247  -m_rotatedTranslatedPoint.head<2>() * m_cam.focalLength /
248  (m_rotatedTranslatedPoint.z() *
249  m_rotatedTranslatedPoint.z()),
250  // with respect to change in incremental rotation
251  getRotationJacobian(),
252  // with respect to change in linear/angular velocity
254  // with respect to change in beacon position
255  getBeaconJacobian();
256  return ret;
257  }
258 
259  void setVariance(double s) {
260  if (s > 0) {
261  m_variance = s;
262  }
263  }
266  return Vector::Constant(m_variance).asDiagonal();
267  }
268 
269  private:
270  double m_variance;
271  Vector m_measurement;
272  CameraModel m_cam;
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;
280  };
281 } // namespace vbtracker
282 } // namespace osvr
283 
284 #endif // INCLUDED_ImagePointMeasurement_h_GUID_BE292A08_8C31_4987_E179_CD2F0CE63183
Eigen::Matrix< Scalar, n, 1 > Vector
A vector of length n.
Definition: FlexibleKalmanBase.h:98
void updateFromState(State const &state)
Updates some internal cached partial solutions.
Definition: ImagePointMeasurement.h:67
Eigen::Matrix< Scalar, n, n > SquareMatrix
A square matrix, n x n.
Definition: FlexibleKalmanBase.h:105
The main namespace for all C++ elements of the framework, internal and external.
Definition: namespace_osvr.dox:3
Eigen::Vector2d projectPoint(double focalLength, Eigen::Vector2d const &principalPoint, Eigen::Vector3d const &camPoint)
Project point for a simple pinhole camera model, with focal lengths equal on both axes and no distort...
Definition: ProjectPoint.h:44
SquareMatrix getCovariance(State &state) const
Definition: ImagePointMeasurement.h:264
View matrix as an upper triangular matrix.
Definition: Constants.h:169
Definition: ImagePointMeasurement.h:46
State type that consists entirely of references to two independent sub-states.
Definition: AugmentedState.h:41
Header.
StateTypeB & b()
Access the second part of the state.
Definition: AugmentedState.h:116
std::size_t DimensionType
Type for dimensions.
Definition: FlexibleKalmanBase.h:51
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:127
Eigen::Matrix< Scalar, m, n > Matrix
A matrix with rows = m, cols = n.
Definition: FlexibleKalmanBase.h:121