WPILibC++ 2025.3.2
Loading...
Searching...
No Matches
UnscentedKalmanFilter.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <functional>
8#include <utility>
9
10#include <Eigen/Cholesky>
11#include <wpi/SymbolExports.h>
12#include <wpi/array.h>
13
14#include "frc/EigenCore.h"
15#include "frc/StateSpaceUtil.h"
21#include "units/time.h"
22
23namespace frc {
24
25/**
26 * A Kalman filter combines predictions from a model and measurements to give an
27 * estimate of the true system state. This is useful because many states cannot
28 * be measured directly as a result of sensor noise, or because the state is
29 * "hidden".
30 *
31 * Kalman filters use a K gain matrix to determine whether to trust the model or
32 * measurements more. Kalman filter theory uses statistics to compute an optimal
33 * K gain which minimizes the sum of squares error in the state estimate. This K
34 * gain is used to correct the state estimate by some amount of the difference
35 * between the actual measurements and the measurements predicted by the model.
36 *
37 * An unscented Kalman filter uses nonlinear state and measurement models. It
38 * propagates the error covariance using sigma points chosen to approximate the
39 * true probability distribution.
40 *
41 * For more on the underlying math, read
42 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9
43 * "Stochastic control theory".
44 *
45 * <p> This class implements a square-root-form unscented Kalman filter
46 * (SR-UKF). The main reason for this is to guarantee that the covariance
47 * matrix remains positive definite.
48 * For more information about the SR-UKF, see
49 * https://www.researchgate.net/publication/3908304.
50 *
51 * @tparam States Number of states.
52 * @tparam Inputs Number of inputs.
53 * @tparam Outputs Number of outputs.
54 */
55template <int States, int Inputs, int Outputs>
57 public:
61
64
66
67 /**
68 * Constructs an unscented Kalman filter.
69 *
70 * See
71 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
72 * for how to select the standard deviations.
73 *
74 * @param f A vector-valued function of x and u that returns
75 * the derivative of the state vector.
76 * @param h A vector-valued function of x and u that returns
77 * the measurement vector.
78 * @param stateStdDevs Standard deviations of model states.
79 * @param measurementStdDevs Standard deviations of measurements.
80 * @param dt Nominal discretization timestep.
81 */
83 std::function<StateVector(const StateVector&, const InputVector&)> f,
84 std::function<OutputVector(const StateVector&, const InputVector&)> h,
85 const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
86 units::second_t dt)
87 : m_f(std::move(f)), m_h(std::move(h)) {
88 m_contQ = MakeCovMatrix(stateStdDevs);
89 m_contR = MakeCovMatrix(measurementStdDevs);
90 m_meanFuncX = [](const Matrixd<States, 2 * States + 1>& sigmas,
92 return sigmas * Wm;
93 };
94 m_meanFuncY = [](const Matrixd<Outputs, 2 * States + 1>& sigmas,
96 return sigmas * Wc;
97 };
98 m_residualFuncX = [](const StateVector& a,
99 const StateVector& b) -> StateVector { return a - b; };
100 m_residualFuncY = [](const OutputVector& a,
101 const OutputVector& b) -> OutputVector {
102 return a - b;
103 };
104 m_addFuncX = [](const StateVector& a, const StateVector& b) -> StateVector {
105 return a + b;
106 };
107 m_dt = dt;
108
109 Reset();
110 }
111
112 /**
113 * Constructs an Unscented Kalman filter with custom mean, residual, and
114 * addition functions. Using custom functions for arithmetic can be useful if
115 * you have angles in the state or measurements, because they allow you to
116 * correctly account for the modular nature of angle arithmetic.
117 *
118 * See
119 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
120 * for how to select the standard deviations.
121 *
122 * @param f A vector-valued function of x and u that returns
123 * the derivative of the state vector.
124 * @param h A vector-valued function of x and u that returns
125 * the measurement vector.
126 * @param stateStdDevs Standard deviations of model states.
127 * @param measurementStdDevs Standard deviations of measurements.
128 * @param meanFuncX A function that computes the mean of 2 * States +
129 * 1 state vectors using a given set of weights.
130 * @param meanFuncY A function that computes the mean of 2 * States +
131 * 1 measurement vectors using a given set of
132 * weights.
133 * @param residualFuncX A function that computes the residual of two
134 * state vectors (i.e. it subtracts them.)
135 * @param residualFuncY A function that computes the residual of two
136 * measurement vectors (i.e. it subtracts them.)
137 * @param addFuncX A function that adds two state vectors.
138 * @param dt Nominal discretization timestep.
139 */
141 std::function<StateVector(const StateVector&, const InputVector&)> f,
142 std::function<OutputVector(const StateVector&, const InputVector&)> h,
143 const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
144 std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
146 meanFuncX,
149 meanFuncY,
150 std::function<StateVector(const StateVector&, const StateVector&)>
151 residualFuncX,
152 std::function<OutputVector(const OutputVector&, const OutputVector&)>
153 residualFuncY,
154 std::function<StateVector(const StateVector&, const StateVector&)>
155 addFuncX,
156 units::second_t dt)
157 : m_f(std::move(f)),
158 m_h(std::move(h)),
159 m_meanFuncX(std::move(meanFuncX)),
160 m_meanFuncY(std::move(meanFuncY)),
161 m_residualFuncX(std::move(residualFuncX)),
162 m_residualFuncY(std::move(residualFuncY)),
163 m_addFuncX(std::move(addFuncX)) {
164 m_contQ = MakeCovMatrix(stateStdDevs);
165 m_contR = MakeCovMatrix(measurementStdDevs);
166 m_dt = dt;
167
168 Reset();
169 }
170
171 /**
172 * Returns the square-root error covariance matrix S.
173 */
174 const StateMatrix& S() const { return m_S; }
175
176 /**
177 * Returns an element of the square-root error covariance matrix S.
178 *
179 * @param i Row of S.
180 * @param j Column of S.
181 */
182 double S(int i, int j) const { return m_S(i, j); }
183
184 /**
185 * Set the current square-root error covariance matrix S.
186 *
187 * @param S The square-root error covariance matrix S.
188 */
189 void SetS(const StateMatrix& S) { m_S = S; }
190
191 /**
192 * Returns the reconstructed error covariance matrix P.
193 */
194 StateMatrix P() const { return m_S * m_S.transpose(); }
195
196 /**
197 * Set the current square-root error covariance matrix S by taking the square
198 * root of P.
199 *
200 * @param P The error covariance matrix P.
201 */
202 void SetP(const StateMatrix& P) { m_S = P.llt().matrixL(); }
203
204 /**
205 * Returns the state estimate x-hat.
206 */
207 const StateVector& Xhat() const { return m_xHat; }
208
209 /**
210 * Returns an element of the state estimate x-hat.
211 *
212 * @param i Row of x-hat.
213 */
214 double Xhat(int i) const { return m_xHat(i); }
215
216 /**
217 * Set initial state estimate x-hat.
218 *
219 * @param xHat The state estimate x-hat.
220 */
221 void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
222
223 /**
224 * Set an element of the initial state estimate x-hat.
225 *
226 * @param i Row of x-hat.
227 * @param value Value for element of x-hat.
228 */
229 void SetXhat(int i, double value) { m_xHat(i) = value; }
230
231 /**
232 * Resets the observer.
233 */
234 void Reset() {
235 m_xHat.setZero();
236 m_S.setZero();
237 m_sigmasF.setZero();
238 }
239
240 /**
241 * Project the model into the future with a new control input u.
242 *
243 * @param u New control input from controller.
244 * @param dt Timestep for prediction.
245 */
246 void Predict(const InputVector& u, units::second_t dt) {
247 m_dt = dt;
248
249 // Discretize Q before projecting mean and covariance forward
250 StateMatrix contA =
252 StateMatrix discA;
253 StateMatrix discQ;
254 DiscretizeAQ<States>(contA, m_contQ, m_dt, &discA, &discQ);
255 Eigen::internal::llt_inplace<double, Eigen::Lower>::blocked(discQ);
256
257 // Generate sigma points around the state mean
258 //
259 // equation (17)
261 m_pts.SquareRootSigmaPoints(m_xHat, m_S);
262
263 // Project each sigma point forward in time according to the
264 // dynamics f(x, u)
265 //
266 // sigmas = 𝒳ₖ₋₁
267 // sigmasF = 𝒳ₖ,ₖ₋₁ or just 𝒳 for readability
268 //
269 // equation (18)
270 for (int i = 0; i < m_pts.NumSigmas(); ++i) {
271 StateVector x = sigmas.template block<States, 1>(0, i);
272 m_sigmasF.template block<States, 1>(0, i) = RK4(m_f, x, u, dt);
273 }
274
275 // Pass the predicted sigmas (𝒳) through the Unscented Transform
276 // to compute the prior state mean and covariance
277 //
278 // equations (18) (19) and (20)
280 m_sigmasF, m_pts.Wm(), m_pts.Wc(), m_meanFuncX, m_residualFuncX,
281 discQ.template triangularView<Eigen::Lower>());
282 m_xHat = xHat;
283 m_S = S;
284 }
285
286 /**
287 * Correct the state estimate x-hat using the measurements in y.
288 *
289 * @param u Same control input used in the predict step.
290 * @param y Measurement vector.
291 */
292 void Correct(const InputVector& u, const OutputVector& y) {
293 Correct<Outputs>(u, y, m_h, m_contR, m_meanFuncY, m_residualFuncY,
294 m_residualFuncX, m_addFuncX);
295 }
296
297 /**
298 * Correct the state estimate x-hat using the measurements in y.
299 *
300 * This is useful for when the measurement noise covariances vary.
301 *
302 * @param u Same control input used in the predict step.
303 * @param y Measurement vector.
304 * @param R Continuous measurement noise covariance matrix.
305 */
306 void Correct(const InputVector& u, const OutputVector& y,
307 const Matrixd<Outputs, Outputs>& R) {
308 Correct<Outputs>(u, y, m_h, R, m_meanFuncY, m_residualFuncY,
309 m_residualFuncX, m_addFuncX);
310 }
311
312 /**
313 * Correct the state estimate x-hat using the measurements in y.
314 *
315 * This is useful for when the measurements available during a timestep's
316 * Correct() call vary. The h(x, u) passed to the constructor is used if one
317 * is not provided (the two-argument version of this function).
318 *
319 * @param u Same control input used in the predict step.
320 * @param y Measurement vector.
321 * @param h A vector-valued function of x and u that returns the measurement
322 * vector.
323 * @param R Continuous measurement noise covariance matrix.
324 */
325 template <int Rows>
327 const InputVector& u, const Vectord<Rows>& y,
328 std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
329 const Matrixd<Rows, Rows>& R) {
330 auto meanFuncY = [](const Matrixd<Outputs, 2 * States + 1>& sigmas,
332 return sigmas * Wc;
333 };
334 auto residualFuncX = [](const StateVector& a,
335 const StateVector& b) -> StateVector {
336 return a - b;
337 };
338 auto residualFuncY = [](const Vectord<Rows>& a,
339 const Vectord<Rows>& b) -> Vectord<Rows> {
340 return a - b;
341 };
342 auto addFuncX = [](const StateVector& a,
343 const StateVector& b) -> StateVector { return a + b; };
344 Correct<Rows>(u, y, std::move(h), R, std::move(meanFuncY),
345 std::move(residualFuncY), std::move(residualFuncX),
346 std::move(addFuncX));
347 }
348
349 /**
350 * Correct the state estimate x-hat using the measurements in y.
351 *
352 * This is useful for when the measurements available during a timestep's
353 * Correct() call vary. The h(x, u) passed to the constructor is used if one
354 * is not provided (the two-argument version of this function).
355 *
356 * @param u Same control input used in the predict step.
357 * @param y Measurement vector.
358 * @param h A vector-valued function of x and u that returns the
359 * measurement vector.
360 * @param R Continuous measurement noise covariance matrix.
361 * @param meanFuncY A function that computes the mean of 2 * States + 1
362 * measurement vectors using a given set of weights.
363 * @param residualFuncY A function that computes the residual of two
364 * measurement vectors (i.e. it subtracts them.)
365 * @param residualFuncX A function that computes the residual of two state
366 * vectors (i.e. it subtracts them.)
367 * @param addFuncX A function that adds two state vectors.
368 */
369 template <int Rows>
371 const InputVector& u, const Vectord<Rows>& y,
372 std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
373 const Matrixd<Rows, Rows>& R,
374 std::function<Vectord<Rows>(const Matrixd<Rows, 2 * States + 1>&,
376 meanFuncY,
377 std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
378 residualFuncY,
379 std::function<StateVector(const StateVector&, const StateVector&)>
380 residualFuncX,
381 std::function<StateVector(const StateVector&, const StateVector&)>
382 addFuncX) {
383 Matrixd<Rows, Rows> discR = DiscretizeR<Rows>(R, m_dt);
384 Eigen::internal::llt_inplace<double, Eigen::Lower>::blocked(discR);
385
386 // Generate new sigma points from the prior mean and covariance
387 // and transform them into measurement space using h(x, u)
388 //
389 // sigmas = 𝒳
390 // sigmasH = 𝒴
391 //
392 // This differs from equation (22) which uses
393 // the prior sigma points, regenerating them allows
394 // multiple measurement updates per time update
397 m_pts.SquareRootSigmaPoints(m_xHat, m_S);
398 for (int i = 0; i < m_pts.NumSigmas(); ++i) {
399 sigmasH.template block<Rows, 1>(0, i) =
400 h(sigmas.template block<States, 1>(0, i), u);
401 }
402
403 // Pass the predicted measurement sigmas through the Unscented Transform
404 // to compute the mean predicted measurement and square-root innovation
405 // covariance.
406 //
407 // equations (23) (24) and (25)
409 sigmasH, m_pts.Wm(), m_pts.Wc(), meanFuncY, residualFuncY,
410 discR.template triangularView<Eigen::Lower>());
411
412 // Compute cross covariance of the predicted state and measurement sigma
413 // points given as:
414 //
415 // 2n
416 // P_{xy} = Σ Wᵢ⁽ᶜ⁾[𝒳ᵢ - x̂][𝒴ᵢ - ŷ⁻]ᵀ
417 // i=0
418 //
419 // equation (26)
421 Pxy.setZero();
422 for (int i = 0; i < m_pts.NumSigmas(); ++i) {
423 Pxy +=
424 m_pts.Wc(i) *
425 (residualFuncX(m_sigmasF.template block<States, 1>(0, i), m_xHat)) *
426 (residualFuncY(sigmasH.template block<Rows, 1>(0, i), yHat))
427 .transpose();
428 }
429
430 // Compute the Kalman gain. We use Eigen's QR decomposition to solve. This
431 // is equivalent to MATLAB's \ operator, so we need to rearrange to use
432 // that.
433 //
434 // K = (P_{xy} / S_{y}ᵀ) / S_{y}
435 // K = (S_{y} \ P_{xy})ᵀ / S_{y}
436 // K = (S_{y}ᵀ \ (S_{y} \ P_{xy}ᵀ))ᵀ
437 //
438 // equation (27)
440 Sy.transpose()
441 .fullPivHouseholderQr()
442 .solve(Sy.fullPivHouseholderQr().solve(Pxy.transpose()))
443 .transpose();
444
445 // Compute the posterior state mean
446 //
447 // x̂ = x̂⁻ + K(y − ŷ⁻)
448 //
449 // second part of equation (27)
450 m_xHat = addFuncX(m_xHat, K * residualFuncY(y, yHat));
451
452 // Compute the intermediate matrix U for downdating
453 // the square-root covariance
454 //
455 // equation (28)
456 Matrixd<States, Rows> U = K * Sy;
457
458 // Downdate the posterior square-root state covariance
459 //
460 // equation (29)
461 for (int i = 0; i < Rows; i++) {
462 Eigen::internal::llt_inplace<double, Eigen::Lower>::rankUpdate(
463 m_S, U.template block<States, 1>(0, i), -1);
464 }
465 }
466
467 private:
468 std::function<StateVector(const StateVector&, const InputVector&)> m_f;
469 std::function<OutputVector(const StateVector&, const InputVector&)> m_h;
470 std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
472 m_meanFuncX;
475 m_meanFuncY;
476 std::function<StateVector(const StateVector&, const StateVector&)>
477 m_residualFuncX;
478 std::function<OutputVector(const OutputVector&, const OutputVector&)>
479 m_residualFuncY;
480 std::function<StateVector(const StateVector&, const StateVector&)> m_addFuncX;
481 StateVector m_xHat;
482 StateMatrix m_S;
483 StateMatrix m_contQ;
486 units::second_t m_dt;
487
489};
490
491extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
492 UnscentedKalmanFilter<3, 3, 1>;
493extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
494 UnscentedKalmanFilter<5, 3, 3>;
495
496} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the Unscente...
Definition MerweScaledSigmaPoints.h:28
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition UnscentedKalmanFilter.h:56
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition UnscentedKalmanFilter.h:207
Matrixd< States, States > StateMatrix
Definition UnscentedKalmanFilter.h:65
const StateMatrix & S() const
Returns the square-root error covariance matrix S.
Definition UnscentedKalmanFilter.h:174
Vectord< Outputs > OutputVector
Definition UnscentedKalmanFilter.h:60
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition UnscentedKalmanFilter.h:214
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition UnscentedKalmanFilter.h:246
void Correct(const InputVector &u, const Vectord< Rows > &y, std::function< Vectord< Rows >(const StateVector &, const InputVector &)> h, const Matrixd< Rows, Rows > &R, std::function< Vectord< Rows >(const Matrixd< Rows, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFuncY, std::function< Vectord< Rows >(const Vectord< Rows > &, const Vectord< Rows > &)> residualFuncY, std::function< StateVector(const StateVector &, const StateVector &)> residualFuncX, std::function< StateVector(const StateVector &, const StateVector &)> addFuncX)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:370
double S(int i, int j) const
Returns an element of the square-root error covariance matrix S.
Definition UnscentedKalmanFilter.h:182
Vectord< States > StateVector
Definition UnscentedKalmanFilter.h:58
void Correct(const InputVector &u, const OutputVector &y, const Matrixd< Outputs, Outputs > &R)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:306
void SetS(const StateMatrix &S)
Set the current square-root error covariance matrix S.
Definition UnscentedKalmanFilter.h:189
UnscentedKalmanFilter(std::function< StateVector(const StateVector &, const InputVector &)> f, std::function< OutputVector(const StateVector &, const InputVector &)> h, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, std::function< StateVector(const Matrixd< States, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFuncX, std::function< OutputVector(const Matrixd< Outputs, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFuncY, std::function< StateVector(const StateVector &, const StateVector &)> residualFuncX, std::function< OutputVector(const OutputVector &, const OutputVector &)> residualFuncY, std::function< StateVector(const StateVector &, const StateVector &)> addFuncX, units::second_t dt)
Constructs an Unscented Kalman filter with custom mean, residual, and addition functions.
Definition UnscentedKalmanFilter.h:140
StateMatrix P() const
Returns the reconstructed error covariance matrix P.
Definition UnscentedKalmanFilter.h:194
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition UnscentedKalmanFilter.h:221
UnscentedKalmanFilter(std::function< StateVector(const StateVector &, const InputVector &)> f, std::function< OutputVector(const StateVector &, const InputVector &)> h, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, units::second_t dt)
Constructs an unscented Kalman filter.
Definition UnscentedKalmanFilter.h:82
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition UnscentedKalmanFilter.h:229
void Correct(const InputVector &u, const Vectord< Rows > &y, std::function< Vectord< Rows >(const StateVector &, const InputVector &)> h, const Matrixd< Rows, Rows > &R)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:326
Vectord< Inputs > InputVector
Definition UnscentedKalmanFilter.h:59
void SetP(const StateMatrix &P)
Set the current square-root error covariance matrix S by taking the square root of P.
Definition UnscentedKalmanFilter.h:202
void Reset()
Resets the observer.
Definition UnscentedKalmanFilter.h:234
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition UnscentedKalmanFilter.h:292
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Definition CAN.h:11
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > SquareRootUnscentedTransform(const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, const Vectord< 2 *States+1 > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFunc, std::function< Vectord< CovDim >(const Vectord< CovDim > &, const Vectord< CovDim > &)> residualFunc, const Matrixd< CovDim, CovDim > &squareRootR)
Computes unscented transform of a set of sigma points and weights.
Definition UnscentedTransform.h:40
T RK4(F &&f, T x, units::second_t dt)
Performs 4th order Runge-Kutta integration of dx/dt = f(x) for dt.
Definition NumericalIntegration.h:23
void DiscretizeAQ(const Matrixd< States, States > &contA, const Matrixd< States, States > &contQ, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, States > *discQ)
Discretizes the given continuous A and Q matrices.
Definition Discretization.h:71
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
Matrixd< Outputs, Outputs > DiscretizeR(const Matrixd< Outputs, Outputs > &R, units::second_t dt)
Returns a discretized version of the provided continuous measurement noise covariance matrix.
Definition Discretization.h:113
constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs)
Creates a covariance matrix from the given vector for use with Kalman filters.
Definition StateSpaceUtil.h:75
auto NumericalJacobianX(F &&f, const Vectord< States > &x, const Vectord< Inputs > &u, Args &&... args)
Returns numerical Jacobian with respect to x for f(x, u, ...).
Definition NumericalJacobian.h:51
Implement std::hash so that hash_code can be used in STL containers.
Definition PointerIntPair.h:280