BiasedGPSFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
16 #pragma once
17 
18 #include <ostream>
19 
20 #include <gtsam/geometry/Pose3.h>
22 
23 namespace gtsam {
24 
30  class BiasedGPSFactor: public NoiseModelFactorN<Pose3, Point3> {
31 
32  private:
33 
36 
39  public:
40 
41  // Provide access to the Matrix& version of evaluateError:
42  using Base::evaluateError;
43 
44  // shorthand for a smart pointer to a factor
45  typedef std::shared_ptr<BiasedGPSFactor> shared_ptr;
46 
49 
51  BiasedGPSFactor(Key posekey, Key biaskey, const Point3 measured,
52  const SharedNoiseModel& model) :
53  Base(model, posekey, biaskey), measured_(measured) {
54  }
55 
56  ~BiasedGPSFactor() override {}
57 
61  void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
62  std::cout << s << "BiasedGPSFactor("
63  << keyFormatter(this->key<1>()) << ","
64  << keyFormatter(this->key<2>()) << ")\n"
65  << " measured: " << measured_.transpose() << std::endl;
66  this->noiseModel_->print(" noise model: ");
67  }
68 
70  bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
71  const This *e = dynamic_cast<const This*> (&expected);
72  return e != nullptr && Base::equals(*e, tol) && traits<Point3>::Equals(this->measured_, e->measured_, tol);
73  }
74 
78  Vector evaluateError(const Pose3& pose, const Point3& bias,
79  OptionalMatrixType H1, OptionalMatrixType H2) const override {
80 
81  if (H1 || H2){
82  H1->resize(3,6); // jacobian wrt pose
83  (*H1) << Z_3x3, pose.rotation().matrix();
84  H2->resize(3,3); // jacobian wrt bias
85  (*H2) << I_3x3;
86  }
87  return pose.translation() + bias - measured_;
88  }
89 
91  const Point3 measured() const {
92  return measured_;
93  }
94 
95  private:
96 
97 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
98 
99  friend class boost::serialization::access;
100  template<class ARCHIVE>
101  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
102  // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
103  ar & boost::serialization::make_nvp("NoiseModelFactor2",
104  boost::serialization::base_object<Base>(*this));
105  ar & BOOST_SERIALIZATION_NVP(measured_);
106  }
107 #endif
108  }; // \class BiasedGPSFactor
109 
110 }
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:308
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:971
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
std::shared_ptr< BiasedGPSFactor > shared_ptr
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
const Point3 measured() const
NoiseModelFactorN< Pose3, Point3 > Base
BiasedGPSFactor(Key posekey, Key biaskey, const Point3 measured, const SharedNoiseModel &model)
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Vector evaluateError(const Pose3 &pose, const Point3 &bias, OptionalMatrixType H1, OptionalMatrixType H2) const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
traits
Definition: chartTesting.h:28
SharedNoiseModel noiseModel_
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
BiasedGPSFactor This
Matrix3 matrix() const
Definition: Rot3M.cpp:218
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:315
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:33:58