2014-01-30 10:22:00 +08:00
|
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
|
|
|
|
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
|
|
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
|
|
* All Rights Reserved
|
|
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* @file MagFactor.h
|
|
|
|
|
|
* @brief Factors involving magnetometers
|
|
|
|
|
|
* @author Frank Dellaert
|
|
|
|
|
|
* @date January 29, 2014
|
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
|
|
#include <gtsam/nonlinear/NonlinearFactor.h>
|
2014-02-01 13:51:52 +08:00
|
|
|
|
#include <gtsam/geometry/Rot2.h>
|
2014-01-30 10:22:00 +08:00
|
|
|
|
#include <gtsam/geometry/Rot3.h>
|
|
|
|
|
|
#include <gtsam/base/LieScalar.h>
|
|
|
|
|
|
|
2014-01-30 10:25:33 +08:00
|
|
|
|
namespace gtsam {
|
2014-01-30 10:22:00 +08:00
|
|
|
|
|
2014-02-01 13:51:52 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* Factor to estimate rotation given magnetometer reading
|
|
|
|
|
|
* This version uses model measured bM = scale * bRn * direction + bias
|
2014-02-01 23:33:17 +08:00
|
|
|
|
* and assumes scale, direction, and the bias are given.
|
|
|
|
|
|
* Rotation is around negative Z axis, i.e. positive is yaw to right!
|
2014-02-01 13:51:52 +08:00
|
|
|
|
*/
|
|
|
|
|
|
class MagFactor: public NoiseModelFactor1<Rot2> {
|
|
|
|
|
|
|
2014-02-01 22:31:22 +08:00
|
|
|
|
const Point3 measured_; ///< The measured magnetometer values
|
2014-02-01 23:29:03 +08:00
|
|
|
|
const Point3 nM_; ///< Local magnetic field (mag output units)
|
2014-02-01 22:31:22 +08:00
|
|
|
|
const Point3 bias_; ///< bias
|
2014-02-01 13:51:52 +08:00
|
|
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
|
|
/** Constructor */
|
2014-02-01 22:31:22 +08:00
|
|
|
|
MagFactor(Key key, const Point3& measured, const LieScalar& scale,
|
|
|
|
|
|
const Sphere2& direction, const Point3& bias,
|
2014-02-01 13:51:52 +08:00
|
|
|
|
const SharedNoiseModel& model) :
|
|
|
|
|
|
NoiseModelFactor1<Rot2>(model, key), //
|
2014-02-01 23:29:03 +08:00
|
|
|
|
measured_(measured), nM_(scale * direction), bias_(bias) {
|
2014-02-01 13:51:52 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/// @return a deep copy of this factor
|
|
|
|
|
|
virtual NonlinearFactor::shared_ptr clone() const {
|
|
|
|
|
|
return boost::static_pointer_cast<NonlinearFactor>(
|
|
|
|
|
|
NonlinearFactor::shared_ptr(new MagFactor(*this)));
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2014-02-01 23:29:03 +08:00
|
|
|
|
static Point3 unrotate(const Rot2& R, const Point3& p,
|
2014-02-01 13:51:52 +08:00
|
|
|
|
boost::optional<Matrix&> HR = boost::none) {
|
2014-02-01 23:33:17 +08:00
|
|
|
|
Point3 q = Rot3::yaw(R.theta()).unrotate(p,HR);
|
2014-02-01 23:29:03 +08:00
|
|
|
|
if (HR) *HR = HR->col(2);
|
2014-02-01 13:51:52 +08:00
|
|
|
|
return q;
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* @brief vector of errors
|
|
|
|
|
|
*/
|
|
|
|
|
|
Vector evaluateError(const Rot2& nRb,
|
|
|
|
|
|
boost::optional<Matrix&> H = boost::none) const {
|
2014-02-01 23:29:03 +08:00
|
|
|
|
// measured bM = nRb<52> * nM + b
|
|
|
|
|
|
Point3 hx = unrotate(nRb, nM_, H) + bias_;
|
2014-02-01 22:31:22 +08:00
|
|
|
|
return (hx - measured_).vector();
|
2014-02-01 13:51:52 +08:00
|
|
|
|
}
|
|
|
|
|
|
};
|
|
|
|
|
|
|
2014-01-30 13:58:15 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* Factor to estimate rotation given magnetometer reading
|
|
|
|
|
|
* This version uses model measured bM = scale * bRn * direction + bias
|
|
|
|
|
|
* and assumes scale, direction, and the bias are given
|
|
|
|
|
|
*/
|
|
|
|
|
|
class MagFactor1: public NoiseModelFactor1<Rot3> {
|
|
|
|
|
|
|
2014-02-01 22:31:22 +08:00
|
|
|
|
const Point3 measured_; ///< The measured magnetometer values
|
|
|
|
|
|
const Point3 nM_; ///< Local magnetic field (mag output units)
|
|
|
|
|
|
const Point3 bias_; ///< bias
|
2014-01-30 13:58:15 +08:00
|
|
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
|
|
/** Constructor */
|
2014-02-01 22:31:22 +08:00
|
|
|
|
MagFactor1(Key key, const Point3& measured, const LieScalar& scale,
|
|
|
|
|
|
const Sphere2& direction, const Point3& bias,
|
2014-01-30 13:58:15 +08:00
|
|
|
|
const SharedNoiseModel& model) :
|
|
|
|
|
|
NoiseModelFactor1<Rot3>(model, key), //
|
2014-02-01 22:31:22 +08:00
|
|
|
|
measured_(measured), nM_(scale * direction), bias_(bias) {
|
2014-01-30 13:58:15 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/// @return a deep copy of this factor
|
|
|
|
|
|
virtual NonlinearFactor::shared_ptr clone() const {
|
|
|
|
|
|
return boost::static_pointer_cast<NonlinearFactor>(
|
|
|
|
|
|
NonlinearFactor::shared_ptr(new MagFactor1(*this)));
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* @brief vector of errors
|
|
|
|
|
|
*/
|
|
|
|
|
|
Vector evaluateError(const Rot3& nRb,
|
|
|
|
|
|
boost::optional<Matrix&> H = boost::none) const {
|
2014-02-01 23:29:03 +08:00
|
|
|
|
// measured bM = nRb<52> * nM + b
|
|
|
|
|
|
Point3 hx = nRb.unrotate(nM_, H) + bias_;
|
2014-02-01 22:31:22 +08:00
|
|
|
|
return (hx - measured_).vector();
|
2014-01-30 13:58:15 +08:00
|
|
|
|
}
|
|
|
|
|
|
};
|
|
|
|
|
|
|
2014-01-30 10:22:00 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* Factor to calibrate local Earth magnetic field as well as magnetometer bias
|
|
|
|
|
|
* This version uses model measured bM = bRn * nM + bias
|
2014-02-01 22:00:36 +08:00
|
|
|
|
* and optimizes for both nM and the bias, where nM is in units defined by magnetometer
|
2014-01-30 10:22:00 +08:00
|
|
|
|
*/
|
2014-02-01 22:31:22 +08:00
|
|
|
|
class MagFactor2: public NoiseModelFactor2<Point3, Point3> {
|
2014-01-30 10:22:00 +08:00
|
|
|
|
|
2014-02-01 22:31:22 +08:00
|
|
|
|
const Point3 measured_; ///< The measured magnetometer values
|
|
|
|
|
|
const Rot3 bRn_; ///< The assumed known rotation from nav to body
|
2014-01-30 10:22:00 +08:00
|
|
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
|
|
/** Constructor */
|
2014-02-01 22:31:22 +08:00
|
|
|
|
MagFactor2(Key key1, Key key2, const Point3& measured, const Rot3& nRb,
|
2014-01-30 10:22:00 +08:00
|
|
|
|
const SharedNoiseModel& model) :
|
2014-02-01 22:31:22 +08:00
|
|
|
|
NoiseModelFactor2<Point3, Point3>(model, key1, key2), //
|
|
|
|
|
|
measured_(measured), bRn_(nRb.inverse()) {
|
2014-01-30 10:22:00 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/// @return a deep copy of this factor
|
|
|
|
|
|
virtual NonlinearFactor::shared_ptr clone() const {
|
|
|
|
|
|
return boost::static_pointer_cast<NonlinearFactor>(
|
2014-01-30 13:58:15 +08:00
|
|
|
|
NonlinearFactor::shared_ptr(new MagFactor2(*this)));
|
2014-01-30 10:22:00 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* @brief vector of errors
|
|
|
|
|
|
* @param nM (unknown) local earth magnetic field vector, in nav frame
|
|
|
|
|
|
* @param bias (unknown) 3D bias
|
|
|
|
|
|
*/
|
2014-02-01 22:31:22 +08:00
|
|
|
|
Vector evaluateError(const Point3& nM, const Point3& bias,
|
2014-01-30 10:22:00 +08:00
|
|
|
|
boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
|
|
|
|
|
|
boost::none) const {
|
|
|
|
|
|
// measured bM = nRb<52> * nM + b, where b is unknown bias
|
2014-02-01 22:31:22 +08:00
|
|
|
|
Point3 hx = bRn_.rotate(nM, boost::none, H1) + bias;
|
2014-01-30 10:22:00 +08:00
|
|
|
|
if (H2)
|
|
|
|
|
|
*H2 = eye(3);
|
2014-02-01 22:31:22 +08:00
|
|
|
|
return (hx - measured_).vector();
|
2014-01-30 10:22:00 +08:00
|
|
|
|
}
|
|
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* Factor to calibrate local Earth magnetic field as well as magnetometer bias
|
|
|
|
|
|
* This version uses model measured bM = scale * bRn * direction + bias
|
|
|
|
|
|
* and optimizes for both scale, direction, and the bias.
|
|
|
|
|
|
*/
|
2014-02-01 22:31:22 +08:00
|
|
|
|
class MagFactor3: public NoiseModelFactor3<LieScalar, Sphere2, Point3> {
|
2014-01-30 10:22:00 +08:00
|
|
|
|
|
2014-02-01 22:31:22 +08:00
|
|
|
|
const Point3 measured_; ///< The measured magnetometer values
|
2014-02-01 22:00:36 +08:00
|
|
|
|
const Rot3 bRn_; ///< The assumed known rotation from nav to body
|
2014-01-30 10:22:00 +08:00
|
|
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
|
|
/** Constructor */
|
2014-02-01 22:31:22 +08:00
|
|
|
|
MagFactor3(Key key1, Key key2, Key key3, const Point3& measured,
|
2014-01-30 10:22:00 +08:00
|
|
|
|
const Rot3& nRb, const SharedNoiseModel& model) :
|
2014-02-01 22:31:22 +08:00
|
|
|
|
NoiseModelFactor3<LieScalar, Sphere2, Point3>(model, key1, key2, key3), //
|
2014-01-30 10:22:00 +08:00
|
|
|
|
measured_(measured), bRn_(nRb.inverse()) {
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/// @return a deep copy of this factor
|
|
|
|
|
|
virtual NonlinearFactor::shared_ptr clone() const {
|
|
|
|
|
|
return boost::static_pointer_cast<NonlinearFactor>(
|
2014-01-30 13:58:15 +08:00
|
|
|
|
NonlinearFactor::shared_ptr(new MagFactor3(*this)));
|
2014-01-30 10:22:00 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* @brief vector of errors
|
|
|
|
|
|
* @param nM (unknown) local earth magnetic field vector, in nav frame
|
|
|
|
|
|
* @param bias (unknown) 3D bias
|
|
|
|
|
|
*/
|
|
|
|
|
|
Vector evaluateError(const LieScalar& scale, const Sphere2& direction,
|
2014-02-01 22:31:22 +08:00
|
|
|
|
const Point3& bias, boost::optional<Matrix&> H1 = boost::none,
|
2014-01-30 10:22:00 +08:00
|
|
|
|
boost::optional<Matrix&> H2 = boost::none, boost::optional<Matrix&> H3 =
|
|
|
|
|
|
boost::none) const {
|
|
|
|
|
|
// measured bM = nRb<52> * nM + b, where b is unknown bias
|
|
|
|
|
|
Sphere2 rotated = bRn_.rotate(direction, boost::none, H2);
|
2014-02-01 22:31:22 +08:00
|
|
|
|
Point3 hx = scale * rotated.point3() + bias;
|
2014-01-30 10:22:00 +08:00
|
|
|
|
if (H1)
|
2014-02-01 22:31:22 +08:00
|
|
|
|
*H1 = rotated.point3().vector();
|
|
|
|
|
|
if (H2) // H2 is 2*2, but we need 3*2
|
2014-01-30 10:22:00 +08:00
|
|
|
|
{
|
|
|
|
|
|
Matrix H;
|
2014-02-01 22:31:22 +08:00
|
|
|
|
rotated.point3(H);
|
2014-01-30 10:22:00 +08:00
|
|
|
|
*H2 = scale * H * (*H2);
|
|
|
|
|
|
}
|
|
|
|
|
|
if (H3)
|
|
|
|
|
|
*H3 = eye(3);
|
2014-02-01 22:31:22 +08:00
|
|
|
|
return (hx - measured_).vector();
|
2014-01-30 10:22:00 +08:00
|
|
|
|
}
|
|
|
|
|
|
};
|
|
|
|
|
|
|
2014-01-30 10:25:33 +08:00
|
|
|
|
}
|
|
|
|
|
|
|