AttitudeFactor.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 
18 #pragma once
19 
21 #include <gtsam/geometry/Pose3.h>
22 #include <gtsam/geometry/Unit3.h>
23 
24 namespace gtsam {
25 
35 
36 protected:
37 
39 
40 public:
41 
44  }
45 
51  AttitudeFactor(const Unit3& nZ, const Unit3& bRef = Unit3(0, 0, 1)) :
52  nZ_(nZ), bRef_(bRef) {
53  }
54 
56  Vector attitudeError(const Rot3& p,
57  OptionalJacobian<2,3> H = {}) const;
58 
59  const Unit3& nZ() const {
60  return nZ_;
61  }
62  const Unit3& bRef() const {
63  return bRef_;
64  }
65 
66 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
67 
68  friend class boost::serialization::access;
69  template<class ARCHIVE>
70  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
71  ar & boost::serialization::make_nvp("nZ_", nZ_);
72  ar & boost::serialization::make_nvp("bRef_", bRef_);
73  }
74 #endif
75 };
76 
81 class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN<Rot3>, public AttitudeFactor {
82 
84 
85 public:
86 
87  // Provide access to the Matrix& version of evaluateError:
88  using Base::evaluateError;
89 
91  typedef std::shared_ptr<Rot3AttitudeFactor> shared_ptr;
92 
95 
98  }
99 
100  ~Rot3AttitudeFactor() override {
101  }
102 
111  const Unit3& bRef = Unit3(0, 0, 1)) :
112  Base(model, key), AttitudeFactor(nZ, bRef) {
113  }
114 
117  return std::static_pointer_cast<gtsam::NonlinearFactor>(
119  }
120 
122  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
123  DefaultKeyFormatter) const override;
124 
126  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
127 
129  Vector evaluateError(const Rot3& nRb, OptionalMatrixType H) const override {
130  return attitudeError(nRb, H);
131  }
132 
133 private:
134 
135 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
136 
137  friend class boost::serialization::access;
138  template<class ARCHIVE>
139  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
140  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
141  ar & boost::serialization::make_nvp("NoiseModelFactor1",
142  boost::serialization::base_object<Base>(*this));
143  ar & boost::serialization::make_nvp("AttitudeFactor",
144  boost::serialization::base_object<AttitudeFactor>(*this));
145  }
146 #endif
147 
148 public:
150 };
151 
153 template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFactor> {};
154 
159 class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,
160  public AttitudeFactor {
161 
163 
164 public:
165 
166  // Provide access to the Matrix& version of evaluateError:
167  using Base::evaluateError;
168 
170  typedef std::shared_ptr<Pose3AttitudeFactor> shared_ptr;
171 
174 
177  }
178 
179  ~Pose3AttitudeFactor() override {
180  }
181 
190  const Unit3& bRef = Unit3(0, 0, 1)) :
191  Base(model, key), AttitudeFactor(nZ, bRef) {
192  }
193 
196  return std::static_pointer_cast<gtsam::NonlinearFactor>(
198  }
199 
201  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
202  DefaultKeyFormatter) const override;
203 
205  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
206 
208  Vector evaluateError(const Pose3& nTb, OptionalMatrixType H) const override {
209  Vector e = attitudeError(nTb.rotation(), H);
210  if (H) {
211  Matrix H23 = *H;
212  *H = Matrix::Zero(2,6);
213  H->block<2,3>(0,0) = H23;
214  }
215  return e;
216  }
217 
218 private:
219 
220 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
221 
222  friend class boost::serialization::access;
223  template<class ARCHIVE>
224  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
225  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
226  ar & boost::serialization::make_nvp("NoiseModelFactor1",
227  boost::serialization::base_object<Base>(*this));
228  ar & boost::serialization::make_nvp("AttitudeFactor",
229  boost::serialization::base_object<AttitudeFactor>(*this));
230  }
231 #endif
232 
233 public:
235 };
236 
238 template<> struct traits<Pose3AttitudeFactor> : public Testable<Pose3AttitudeFactor> {};
239 
240 }
241 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const gtsam::Symbol key('X', 0)
NoiseModelFactorN< Pose3 > Base
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:971
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Unit3 bRef_
Position measurement in.
Vector evaluateError(const Rot3 &nRb, OptionalMatrixType H) const override
Vector attitudeError(const Rot3 &p, OptionalJacobian< 2, 3 > H={}) const
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange [*:*] noreverse nowriteback set trange [*:*] noreverse nowriteback set urange [*:*] noreverse nowriteback set vrange [*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::NonlinearFactor::shared_ptr clone() const override
Rot3AttitudeFactor This
Typedef to this class.
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Pose3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
const Rot3 nRb
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
const Unit3 & nZ() const
const Unit3 & bRef() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
AttitudeFactor(const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
Vector evaluateError(const Pose3 &nTb, OptionalMatrixType H) 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
#define This
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
std::shared_ptr< Pose3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
std::shared_ptr< This > shared_ptr
float * p
NoiseModelFactorN< Rot3 > Base
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:315
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
const G double tol
Definition: Group.h:86
gtsam::NonlinearFactor::shared_ptr clone() const override
3D Pose
Pose3AttitudeFactor This
Typedef to this class.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::shared_ptr< Rot3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
Rot3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.


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