GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
PartialPriorFactor.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/base/Lie.h>
22 
23 namespace gtsam {
24 
37  template<class VALUE>
38  class PartialPriorFactor: public NoiseModelFactorN<VALUE> {
39 
40  public:
41  typedef VALUE T;
42 
43  protected:
44  // Concept checks on the variable type - currently requires Lie
45  GTSAM_CONCEPT_LIE_TYPE(VALUE)
46 
49 
50  Vector prior_;
51  std::vector<size_t> indices_;
52 
55 
61  : Base(model, key) {}
62 
63  public:
64 
65  // Provide access to the Matrix& version of evaluateError:
66  using Base::evaluateError;
67 
68  ~PartialPriorFactor() override {}
69 
71  PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) :
72  Base(model, key),
73  prior_((Vector(1) << prior).finished()),
74  indices_(1, idx) {
75  assert(model->dim() == 1);
76  }
77 
79  PartialPriorFactor(Key key, const std::vector<size_t>& indices, const Vector& prior,
80  const SharedNoiseModel& model) :
81  Base(model, key),
82  prior_(prior),
83  indices_(indices) {
84  assert((size_t)prior_.size() == indices_.size());
85  assert(model->dim() == (size_t)prior.size());
86  }
87 
89  gtsam::NonlinearFactor::shared_ptr clone() const override {
90  return std::static_pointer_cast<gtsam::NonlinearFactor>(
91  gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
92 
96  void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
97  Base::print(s, keyFormatter);
98  gtsam::print(prior_, "prior");
99  }
100 
102  bool equals(const NonlinearFactor& expected, double tol=1e-9) const override {
103  const This *e = dynamic_cast<const This*> (&expected);
104  return e != nullptr && Base::equals(*e, tol) &&
105  gtsam::equal_with_abs_tol(this->prior_, e->prior_, tol) &&
106  this->indices_ == e->indices_;
107  }
108 
112  Vector evaluateError(const T& p, OptionalMatrixType H) const override {
113  Eigen::Matrix<double, T::dimension, T::dimension> H_local;
114 
115  // If the Rot3 Cayley map is used, Rot3::LocalCoordinates will throw a runtime error
116  // when asked to compute the Jacobian matrix (see Rot3M.cpp).
117  #ifdef GTSAM_ROT3_EXPMAP
118  const Vector full_tangent = T::LocalCoordinates(p, H ? &H_local : nullptr);
119  #else
120  const Vector full_tangent = T::Logmap(p, H ? &H_local : nullptr);
121  #endif
122 
123  if (H) {
124  (*H) = Matrix::Zero(indices_.size(), T::dimension);
125  for (size_t i = 0; i < indices_.size(); ++i) {
126  (*H).row(i) = H_local.row(indices_.at(i));
127  }
128  }
129  // Select relevant parameters from the tangent vector.
130  Vector partial_tangent = Vector::Zero(indices_.size());
131  for (size_t i = 0; i < indices_.size(); ++i) {
132  partial_tangent(i) = full_tangent(indices_.at(i));
133  }
134 
135  return partial_tangent - prior_;
136  }
137 
138  // access
139  const Vector& prior() const { return prior_; }
140  const std::vector<size_t>& indices() const { return indices_; }
141 
142  private:
143 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
144 
145  friend class boost::serialization::access;
146  template<class ARCHIVE>
147  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
148  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
149  ar & boost::serialization::make_nvp("NoiseModelFactor1",
150  boost::serialization::base_object<Base>(*this));
151  ar & BOOST_SERIALIZATION_NVP(prior_);
152  ar & BOOST_SERIALIZATION_NVP(indices_);
153  // ar & BOOST_SERIALIZATION_NVP(H_);
154  }
155 #endif
156  }; // \class PartialPriorFactor
157 
158 }
Definition: NonlinearFactor.h:431
PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel &model)
Definition: PartialPriorFactor.h:71
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Definition: Factor.h:69
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
PartialPriorFactor(Key key, const std::vector< size_t > &indices, const Vector &prior, const SharedNoiseModel &model)
Definition: PartialPriorFactor.h:79
Key key() const
Definition: NonlinearFactor.h:582
Definition: NonlinearFactor.h:68
PartialPriorFactor()
Definition: PartialPriorFactor.h:54
std::vector< size_t > indices_
Indices of the measured tangent space parameters.
Definition: PartialPriorFactor.h:51
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: PartialPriorFactor.h:89
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
PartialPriorFactor(Key key, const SharedNoiseModel &model)
Definition: PartialPriorFactor.h:60
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
Base class and basic functions for Lie types.
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: Matrix.h:80
Definition: chartTesting.h:28
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: PartialPriorFactor.h:96
Vector prior_
Measurement on tangent space parameters, in compressed form.
Definition: PartialPriorFactor.h:50
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Definition: PartialPriorFactor.h:102
Definition: PartialPriorFactor.h:38
Vector evaluateError(const T &p, OptionalMatrixType H) const override
Definition: PartialPriorFactor.h:112
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741