ReferenceFrameFactor.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 
12 /*
13  * @file ReferenceFrameFactor.h
14  * @brief A constraint for combining graphs by common landmarks and a transform node
15  * @author Alex Cunningham
16  */
17 
18 #pragma once
19 
21 
22 namespace gtsam {
23 
29 template<class T, class P>
31  const T& trans, const P& global,
32  OptionalMatrixType Dtrans,
33  OptionalMatrixType Dglobal) {
34  return trans.transformFrom(global, Dtrans, Dglobal);
35 }
36 
56 template<class POINT, class TRANSFORM>
57 class ReferenceFrameFactor : public NoiseModelFactorN<POINT, TRANSFORM, POINT> {
58 protected:
61 
62 public:
65 
66  // Provide access to the Matrix& version of evaluateError:
67  using Base::evaluateError;
68 
69  typedef POINT Point;
70  typedef TRANSFORM Transform;
71 
75  ReferenceFrameFactor(Key globalKey, Key transKey, Key localKey, const noiseModel::Base::shared_ptr& model)
76  : Base(model,globalKey, transKey, localKey) {}
77 
82  ReferenceFrameFactor(double mu, Key globalKey, Key transKey, Key localKey)
83  : Base(globalKey, transKey, localKey, Point().dim(), mu) {}
84 
89  ReferenceFrameFactor(Key globalKey, Key transKey, Key localKey, double sigma = 1e-2)
90  : Base(noiseModel::Isotropic::Sigma(traits<POINT>::dimension, sigma),
91  globalKey, transKey, localKey) {}
92 
93  ~ReferenceFrameFactor() override{}
94 
96  return std::static_pointer_cast<NonlinearFactor>(
97  NonlinearFactor::shared_ptr(new This(*this))); }
98 
100  Vector evaluateError(const Point& global, const Transform& trans, const Point& local,
101  OptionalMatrixType Dforeign, OptionalMatrixType Dtrans,
102  OptionalMatrixType Dlocal) const override {
103  Point newlocal = transform_point<Transform,Point>(trans, global, Dtrans, Dforeign);
104  if (Dlocal) {
105  *Dlocal = -1* Matrix::Identity(traits<Point>::dimension, traits<Point>::dimension);
106  }
107  return traits<Point>::Local(local,newlocal);
108  }
109 
110  void print(const std::string& s="",
111  const gtsam::KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
112  std::cout << s << ": ReferenceFrameFactor("
113  << "Global: " << keyFormatter(this->key1()) << ","
114  << " Transform: " << keyFormatter(this->key2()) << ","
115  << " Local: " << keyFormatter(this->key3()) << ")\n";
116  this->noiseModel_->print(" noise model");
117  }
118 
119  // access - convenience functions
120  Key global_key() const { return this->key1(); }
121  Key transform_key() const { return this->key2(); }
122  Key local_key() const { return this->key3(); }
123 
124 private:
125 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
126 
127  friend class boost::serialization::access;
128  template<class ARCHIVE>
129  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
130  ar & boost::serialization::make_nvp("NonlinearFactor3",
131  boost::serialization::base_object<Base>(*this));
132  }
133 #endif
134 };
135 
137 template<class T1, class T2>
138 struct traits<ReferenceFrameFactor<T1, T2> > : public Testable<ReferenceFrameFactor<T1, T2> > {};
139 
140 } // \namespace gtsam
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
gtsam::transform_point
P transform_point(const T &trans, const P &global, OptionalMatrixType Dtrans, OptionalMatrixType Dglobal)
Definition: ReferenceFrameFactor.h:30
gtsam::NoiseModelFactor::dim
size_t dim() const override
Definition: NonlinearFactor.h:240
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::noiseModel::Base::shared_ptr
std::shared_ptr< Base > shared_ptr
Definition: NoiseModel.h:60
mu
double mu
Definition: testBoundingConstraint.cpp:37
gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT >::evaluateError
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
gtsam::ReferenceFrameFactor::clone
NonlinearFactor::shared_ptr clone() const override
Definition: ReferenceFrameFactor.h:95
gtsam::Factor
Definition: Factor.h:69
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:205
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:169
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::ReferenceFrameFactor::~ReferenceFrameFactor
~ReferenceFrameFactor() override
Definition: ReferenceFrameFactor.h:93
gtsam::ReferenceFrameFactor::Transform
TRANSFORM Transform
Definition: ReferenceFrameFactor.h:70
gtsam::ReferenceFrameFactor::transform_key
Key transform_key() const
Definition: ReferenceFrameFactor.h:121
gtsam::ReferenceFrameFactor::evaluateError
Vector evaluateError(const Point &global, const Transform &trans, const Point &local, OptionalMatrixType Dforeign, OptionalMatrixType Dtrans, OptionalMatrixType Dlocal) const override
Definition: ReferenceFrameFactor.h:100
gtsam::NoiseModelFactor::noiseModel
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:245
gtsam::KeyFormatter
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
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::ReferenceFrameFactor::ReferenceFrameFactor
ReferenceFrameFactor(Key globalKey, Key transKey, Key localKey, double sigma=1e-2)
Definition: ReferenceFrameFactor.h:89
gtsam::ReferenceFrameFactor
Definition: ReferenceFrameFactor.h:57
gtsam::ReferenceFrameFactor::global_key
Key global_key() const
Definition: ReferenceFrameFactor.h:120
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
Eigen::Triplet
A small structure to hold a non zero as a triplet (i,j,value).
Definition: SparseUtil.h:162
gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT >::key1
Key key1() const
Definition: NonlinearFactor.h:731
gtsam::ReferenceFrameFactor::This
ReferenceFrameFactor< POINT, TRANSFORM > This
Definition: ReferenceFrameFactor.h:64
gtsam::ReferenceFrameFactor::print
void print(const std::string &s="", const gtsam::KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: ReferenceFrameFactor.h:110
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::ReferenceFrameFactor::ReferenceFrameFactor
ReferenceFrameFactor(Key globalKey, Key transKey, Key localKey, const noiseModel::Base::shared_ptr &model)
Definition: ReferenceFrameFactor.h:75
NonlinearFactor.h
Non-linear factor base classes.
gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT >::key2
Key key2() const
Definition: NonlinearFactor.h:735
gtsam::ReferenceFrameFactor::ReferenceFrameFactor
ReferenceFrameFactor(double mu, Key globalKey, Key transKey, Key localKey)
Definition: ReferenceFrameFactor.h:82
gtsam::ReferenceFrameFactor::ReferenceFrameFactor
ReferenceFrameFactor()
Definition: ReferenceFrameFactor.h:60
gtsam::ReferenceFrameFactor::Base
NoiseModelFactorN< POINT, TRANSFORM, POINT > Base
Definition: ReferenceFrameFactor.h:63
gtsam::ReferenceFrameFactor::Point
POINT Point
Definition: ReferenceFrameFactor.h:69
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
gtsam::trans
Matrix trans(const Matrix &A)
Definition: base/Matrix.h:241
P
static double P[]
Definition: ellpe.c:68
gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT >::key3
Key key3() const
Definition: NonlinearFactor.h:740
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::ReferenceFrameFactor::local_key
Key local_key() const
Definition: ReferenceFrameFactor.h:122


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:04:53