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 = boost::none) const;
58 
59  const Unit3& nZ() const {
60  return nZ_;
61  }
62  const Unit3& bRef() const {
63  return bRef_;
64  }
65 
68  template<class ARCHIVE>
69  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
70  ar & boost::serialization::make_nvp("nZ_", nZ_);
71  ar & boost::serialization::make_nvp("bRef_", bRef_);
72  }
73 };
74 
79 class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public AttitudeFactor {
80 
82 
83 public:
84 
86  typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr;
87 
90 
93  }
94 
95  ~Rot3AttitudeFactor() override {
96  }
97 
106  const Unit3& bRef = Unit3(0, 0, 1)) :
107  Base(model, key), AttitudeFactor(nZ, bRef) {
108  }
109 
112  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
114  }
115 
117  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
118  DefaultKeyFormatter) const override;
119 
121  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
122 
125  boost::optional<Matrix&> H = boost::none) const override {
126  return attitudeError(nRb, H);
127  }
128 
129 private:
130 
132  friend class boost::serialization::access;
133  template<class ARCHIVE>
134  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
135  ar & boost::serialization::make_nvp("NoiseModelFactor1",
136  boost::serialization::base_object<Base>(*this));
137  ar & boost::serialization::make_nvp("AttitudeFactor",
138  boost::serialization::base_object<AttitudeFactor>(*this));
139  }
140 
141 public:
143 };
144 
146 template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFactor> {};
147 
152 class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
153  public AttitudeFactor {
154 
156 
157 public:
158 
160  typedef boost::shared_ptr<Pose3AttitudeFactor> shared_ptr;
161 
164 
167  }
168 
169  ~Pose3AttitudeFactor() override {
170  }
171 
180  const Unit3& bRef = Unit3(0, 0, 1)) :
181  Base(model, key), AttitudeFactor(nZ, bRef) {
182  }
183 
186  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
188  }
189 
191  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
192  DefaultKeyFormatter) const override;
193 
195  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
196 
198  Vector evaluateError(const Pose3& nTb, //
199  boost::optional<Matrix&> H = boost::none) const override {
200  Vector e = attitudeError(nTb.rotation(), H);
201  if (H) {
202  Matrix H23 = *H;
203  *H = Matrix::Zero(2,6);
204  H->block<2,3>(0,0) = H23;
205  }
206  return e;
207  }
208 
209 private:
210 
212  friend class boost::serialization::access;
213  template<class ARCHIVE>
214  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
215  ar & boost::serialization::make_nvp("NoiseModelFactor1",
216  boost::serialization::base_object<Base>(*this));
217  ar & boost::serialization::make_nvp("AttitudeFactor",
218  boost::serialization::base_object<AttitudeFactor>(*this));
219  }
220 
221 public:
223 };
224 
226 template<> struct traits<Pose3AttitudeFactor> : public Testable<Pose3AttitudeFactor> {};
227 
228 }
229 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const Unit3 & nZ() const
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
NoiseModelFactor1< Pose3 > Base
Vector evaluateError(const Rot3 &nRb, boost::optional< Matrix & > H=boost::none) const override
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Unit3 bRef_
Position measurement in.
void serialize(ARCHIVE &ar, const unsigned int)
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
friend class boost::serialization::access
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
gtsam::NonlinearFactor::shared_ptr clone() const override
Rot3AttitudeFactor This
Typedef to this class.
boost::shared_ptr< Pose3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
void serialize(ARCHIVE &ar, const unsigned int)
Pose3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< This > shared_ptr
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
AttitudeFactor(const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
#define This
Vector evaluateError(const Pose3 &nTb, boost::optional< Matrix & > H=boost::none) const override
traits
Definition: chartTesting.h:28
NoiseModelFactor1< Rot3 > Base
boost::shared_ptr< Rot3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
Non-linear factor base classes.
Vector attitudeError(const Rot3 &p, OptionalJacobian< 2, 3 > H=boost::none) const
const Unit3 & bRef() const
float * p
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
const G double tol
Definition: Group.h:83
gtsam::NonlinearFactor::shared_ptr clone() const override
void serialize(ARCHIVE &ar, const unsigned int)
Rot3 nRb
3D Pose
Pose3AttitudeFactor This
Typedef to this class.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
Rot3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:39