gtsam  4.0.0
gtsam
AttitudeFactor.h
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 
38  const Unit3 nZ_, bRef_;
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 
61  template<class ARCHIVE>
62  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
63  ar & boost::serialization::make_nvp("nZ_", const_cast<Unit3&>(nZ_));
64  ar & boost::serialization::make_nvp("bRef_", const_cast<Unit3&>(bRef_));
65  }
66 };
67 
72 class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public AttitudeFactor {
73 
75 
76 public:
77 
79  typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr;
80 
83 
86  }
87 
88  virtual ~Rot3AttitudeFactor() {
89  }
90 
98  Rot3AttitudeFactor(Key key, const Unit3& nZ, const SharedNoiseModel& model,
99  const Unit3& bRef = Unit3(0, 0, 1)) :
100  Base(model, key), AttitudeFactor(nZ, bRef) {
101  }
102 
104  virtual gtsam::NonlinearFactor::shared_ptr clone() const {
105  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
106  gtsam::NonlinearFactor::shared_ptr(new This(*this)));
107  }
108 
110  virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
111  DefaultKeyFormatter) const;
112 
114  virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const;
115 
117  virtual Vector evaluateError(const Rot3& nRb, //
118  boost::optional<Matrix&> H = boost::none) const {
119  return attitudeError(nRb, H);
120  }
121  Unit3 nZ() const {
122  return nZ_;
123  }
124  Unit3 bRef() const {
125  return bRef_;
126  }
127 
128 private:
129 
131  friend class boost::serialization::access;
132  template<class ARCHIVE>
133  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
134  ar & boost::serialization::make_nvp("NoiseModelFactor1",
135  boost::serialization::base_object<Base>(*this));
136  ar & boost::serialization::make_nvp("AttitudeFactor",
137  boost::serialization::base_object<AttitudeFactor>(*this));
138  }
139 
140 public:
141  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
142 };
143 
145 template<> struct traits<Rot3AttitudeFactor> : public Testable<Rot3AttitudeFactor> {};
146 
151 class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
152  public AttitudeFactor {
153 
155 
156 public:
157 
159  typedef boost::shared_ptr<Pose3AttitudeFactor> shared_ptr;
160 
163 
166  }
167 
168  virtual ~Pose3AttitudeFactor() {
169  }
170 
178  Pose3AttitudeFactor(Key key, const Unit3& nZ, const SharedNoiseModel& model,
179  const Unit3& bRef = Unit3(0, 0, 1)) :
180  Base(model, key), AttitudeFactor(nZ, bRef) {
181  }
182 
184  virtual gtsam::NonlinearFactor::shared_ptr clone() const {
185  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
186  gtsam::NonlinearFactor::shared_ptr(new This(*this)));
187  }
188 
190  virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
191  DefaultKeyFormatter) const;
192 
194  virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const;
195 
197  virtual Vector evaluateError(const Pose3& nTb, //
198  boost::optional<Matrix&> H = boost::none) const {
199  Vector e = attitudeError(nTb.rotation(), H);
200  if (H) {
201  Matrix H23 = *H;
202  *H = Matrix::Zero(2,6);
203  H->block<2,3>(0,0) = H23;
204  }
205  return e;
206  }
207  Unit3 nZ() const {
208  return nZ_;
209  }
210  Unit3 bRef() const {
211  return bRef_;
212  }
213 
214 private:
215 
217  friend class boost::serialization::access;
218  template<class ARCHIVE>
219  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
220  ar & boost::serialization::make_nvp("NoiseModelFactor1",
221  boost::serialization::base_object<Base>(*this));
222  ar & boost::serialization::make_nvp("AttitudeFactor",
223  boost::serialization::base_object<AttitudeFactor>(*this));
224  }
225 
226 public:
227  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
228 };
229 
231 template<> struct traits<Pose3AttitudeFactor> : public Testable<Pose3AttitudeFactor> {};
232 
233 }
234 
Definition: AttitudeFactor.h:72
This is the base class for all factor types.
Definition: Factor.h:54
virtual Vector evaluateError(const Rot3 &nRb, boost::optional< Matrix & > H=boost::none) const
vector of errors
Definition: AttitudeFactor.h:117
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
boost::shared_ptr< Pose3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: AttitudeFactor.h:159
Definition: AttitudeFactor.h:151
Definition: AttitudeFactor.h:34
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
virtual Vector evaluateError(const Pose3 &nTb, boost::optional< Matrix & > H=boost::none) const
vector of errors
Definition: AttitudeFactor.h:197
Rot3AttitudeFactor This
Typedef to this class.
Definition: AttitudeFactor.h:82
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: AttitudeFactor.h:184
Template to create a binary predicate.
Definition: Testable.h:110
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
Pose3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
Definition: AttitudeFactor.h:178
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Definition: Rot3.h:56
Pose3AttitudeFactor()
default constructor - only use for serialization
Definition: AttitudeFactor.h:165
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
A convenient base class for creating your own NoiseModelFactor with 1 variable.
Definition: NonlinearFactor.h:276
boost::shared_ptr< Rot3AttitudeFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: AttitudeFactor.h:79
Vector attitudeError(const Rot3 &p, OptionalJacobian< 2, 3 > H=boost::none) const
vector of errors
Definition: AttitudeFactor.cpp:26
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
const Unit3 bRef_
Position measurement in.
Definition: AttitudeFactor.h:38
Rot3AttitudeFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
Definition: AttitudeFactor.h:98
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Non-linear factor base classes.
3D Pose
AttitudeFactor(const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
Definition: AttitudeFactor.h:51
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: AttitudeFactor.h:104
Pose3AttitudeFactor This
Typedef to this class.
Definition: AttitudeFactor.h:162
const Rot3 & rotation(OptionalJacobian< 3, 6 > H=boost::none) const
get rotation
Definition: Pose3.cpp:272
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
Rot3AttitudeFactor()
default constructor - only use for serialization
Definition: AttitudeFactor.h:85
AttitudeFactor()
default constructor - only use for serialization
Definition: AttitudeFactor.h:43
Definition: Pose3.h:37
friend class boost::serialization::access
Serialization function.
Definition: AttitudeFactor.h:60