NonlinearEquality.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 NonlinearEquality.h
14  * @brief Factor to handle enforced equality between factors
15  * @author Alex Cunningham
16  */
17 
18 #pragma once
19 
21 #include <gtsam/base/Testable.h>
22 #include <gtsam/base/Manifold.h>
23 
24 #include <boost/bind.hpp>
25 
26 #include <limits>
27 #include <iostream>
28 #include <cmath>
29 
30 namespace gtsam {
31 
44 template<class VALUE>
45 class NonlinearEquality: public NoiseModelFactor1<VALUE> {
46 
47 public:
48  typedef VALUE T;
49 
50 private:
51 
52  // feasible value
54 
55  // error handling flag
57 
58  // error gain in allow error case
59  double error_gain_;
60 
61  // typedef to this class
63 
64  // typedef to base class
66 
67 public:
68 
72  typedef boost::function<bool(const T&, const T&)> CompareFunction;
73  CompareFunction compare_;
74 // bool (*compare_)(const T& a, const T& b);
75 
78  }
79 
80  ~NonlinearEquality() override {
81  }
82 
85 
89  NonlinearEquality(Key j, const T& feasible,
90  const CompareFunction &_compare = boost::bind(traits<T>::Equals,_1,_2,1e-9)) :
91  Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
92  j), feasible_(feasible), allow_error_(false), error_gain_(0.0), //
93  compare_(_compare) {
94  }
95 
99  NonlinearEquality(Key j, const T& feasible, double error_gain,
100  const CompareFunction &_compare = boost::bind(traits<T>::Equals,_1,_2,1e-9)) :
101  Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
102  j), feasible_(feasible), allow_error_(true), error_gain_(error_gain), //
103  compare_(_compare) {
104  }
105 
109 
110  void print(const std::string& s = "",
111  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
112  std::cout << s << "Constraint: on [" << keyFormatter(this->key()) << "]\n";
113  traits<VALUE>::Print(feasible_, "Feasible Point:\n");
114  std::cout << "Variable Dimension: " << traits<T>::GetDimension(feasible_) << std::endl;
115  }
116 
118  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
119  const This* e = dynamic_cast<const This*>(&f);
120  return e && Base::equals(f) && traits<T>::Equals(feasible_,e->feasible_, tol)
121  && std::abs(error_gain_ - e->error_gain_) < tol;
122  }
123 
127 
129  double error(const Values& c) const override {
130  const T& xj = c.at<T>(this->key());
131  Vector e = this->unwhitenedError(c);
132  if (allow_error_ || !compare_(xj, feasible_)) {
133  return error_gain_ * dot(e, e);
134  } else {
135  return 0.0;
136  }
137  }
138 
140  Vector evaluateError(const T& xj,
141  boost::optional<Matrix&> H = boost::none) const override {
142  const size_t nj = traits<T>::GetDimension(feasible_);
143  if (allow_error_) {
144  if (H)
145  *H = Matrix::Identity(nj,nj); // FIXME: this is not the right linearization for nonlinear compare
146  return traits<T>::Local(xj,feasible_);
147  } else if (compare_(feasible_, xj)) {
148  if (H)
149  *H = Matrix::Identity(nj,nj);
150  return Vector::Zero(nj); // set error to zero if equal
151  } else {
152  if (H)
153  throw std::invalid_argument(
154  "Linearization point not feasible for "
155  + DefaultKeyFormatter(this->key()) + "!");
156  return Vector::Constant(nj, std::numeric_limits<double>::infinity()); // set error to infinity if not equal
157  }
158  }
159 
160  // Linearize is over-written, because base linearization tries to whiten
161  GaussianFactor::shared_ptr linearize(const Values& x) const override {
162  const T& xj = x.at<T>(this->key());
163  Matrix A;
164  Vector b = evaluateError(xj, A);
167  new JacobianFactor(this->key(), A, b, model));
168  }
169 
172  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
174  }
175 
177 
179 
180 private:
181 
184  template<class ARCHIVE>
185  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
186  ar
187  & boost::serialization::make_nvp("NoiseModelFactor1",
188  boost::serialization::base_object<Base>(*this));
189  ar & BOOST_SERIALIZATION_NVP(feasible_);
190  ar & BOOST_SERIALIZATION_NVP(allow_error_);
191  ar & BOOST_SERIALIZATION_NVP(error_gain_);
192  }
193 
194 };
195 // \class NonlinearEquality
196 
197 template<typename VALUE>
198 struct traits<NonlinearEquality<VALUE> > : Testable<NonlinearEquality<VALUE> > {
199 };
200 
201 /* ************************************************************************* */
205 template<class VALUE>
206 class NonlinearEquality1: public NoiseModelFactor1<VALUE> {
207 
208 public:
209  typedef VALUE X;
210 
211 protected:
214 
217  }
218 
219  X value_;
220 
222 
224 
225 public:
226 
228 
236  NonlinearEquality1(const X& value, Key key, double mu = 1000.0) :
237  Base( noiseModel::Constrained::All(traits<X>::GetDimension(value),
238  std::abs(mu)), key), value_(value) {
239  }
240 
241  ~NonlinearEquality1() override {
242  }
243 
246  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
248  }
249 
252  boost::optional<Matrix&> H = boost::none) const override {
253  if (H)
254  (*H) = Matrix::Identity(traits<X>::GetDimension(x1),traits<X>::GetDimension(x1));
255  // manifold equivalent of h(x)-z -> log(z,h(x))
256  return traits<X>::Local(value_,x1);
257  }
258 
260  void print(const std::string& s = "",
261  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
262  std::cout << s << ": NonlinearEquality1(" << keyFormatter(this->key())
263  << ")," << "\n";
264  this->noiseModel_->print();
265  traits<X>::Print(value_, "Value");
266  }
267 
269 
270 private:
271 
273  friend class boost::serialization::access;
274  template<class ARCHIVE>
275  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
276  ar
277  & boost::serialization::make_nvp("NoiseModelFactor1",
278  boost::serialization::base_object<Base>(*this));
279  ar & BOOST_SERIALIZATION_NVP(value_);
280  }
281 };
282 // \NonlinearEquality1
283 
284 template<typename VALUE>
285 struct traits<NonlinearEquality1<VALUE> > : Testable<NonlinearEquality1<VALUE> > {
286 };
287 
288 /* ************************************************************************* */
293 template<class VALUE>
294 class NonlinearEquality2: public NoiseModelFactor2<VALUE, VALUE> {
295 public:
296  typedef VALUE X;
297 
298 protected:
301 
303 
304 
306  }
307 
308 public:
309 
310  typedef boost::shared_ptr<NonlinearEquality2<VALUE> > shared_ptr;
311 
313  NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) :
314  Base(noiseModel::Constrained::All(traits<X>::dimension, std::abs(mu)), key1, key2) {
315  }
316  ~NonlinearEquality2() override {
317  }
318 
321  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
323  }
324 
326  Vector evaluateError(const X& x1, const X& x2, boost::optional<Matrix&> H1 =
327  boost::none, boost::optional<Matrix&> H2 = boost::none) const override {
328  static const size_t p = traits<X>::dimension;
329  if (H1) *H1 = -Matrix::Identity(p,p);
330  if (H2) *H2 = Matrix::Identity(p,p);
331  return traits<X>::Local(x1,x2);
332  }
333 
335 
336 private:
337 
339  friend class boost::serialization::access;
340  template<class ARCHIVE>
341  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
342  ar
343  & boost::serialization::make_nvp("NoiseModelFactor2",
344  boost::serialization::base_object<Base>(*this));
345  }
346 };
347 // \NonlinearEquality2
348 
349 template<typename VALUE>
350 struct traits<NonlinearEquality2<VALUE> > : Testable<NonlinearEquality2<VALUE> > {
351 };
352 
353 
354 }// namespace gtsam
355 
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Concept check for values that can be used in unit tests.
gtsam::NonlinearFactor::shared_ptr clone() const override
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:194
noiseModel::Diagonal::shared_ptr model
double mu
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::NonlinearFactor::shared_ptr clone() const override
void serialize(ARCHIVE &ar, const unsigned int)
Definition: Half.h:150
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Vector evaluateError(const T &xj, boost::optional< Matrix & > H=boost::none) const override
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
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
Definition: Testable.h:175
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const SharedNoiseModel & noiseModel() const
access to the noise model
NoiseModelFactor1< VALUE > Base
NoiseModelFactor1< VALUE > Base
const Symbol key1('v', 1)
GaussianFactor::shared_ptr linearize(const Values &x) const override
NonlinearEquality(Key j, const T &feasible, const CompareFunction &_compare=boost::bind(traits< T >::Equals, _1, _2, 1e-9))
gtsam::NonlinearFactor::shared_ptr clone() const override
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Eigen::VectorXd Vector
Definition: Vector.h:38
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
const ValueType at(Key j) const
Definition: Values-inl.h:342
boost::function< bool(const T &, const T &)> CompareFunction
Vector evaluateError(const X &x1, boost::optional< Matrix & > H=boost::none) const override
Base class and basic functions for Manifold types.
friend class boost::serialization::access
NonlinearEquality(Key j, const T &feasible, double error_gain, const CompareFunction &_compare=boost::bind(traits< T >::Equals, _1, _2, 1e-9))
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
void serialize(ARCHIVE &ar, const unsigned int)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
boost::shared_ptr< NonlinearEquality2< VALUE > > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
NonlinearEquality2(Key key1, Key key2, double mu=1000.0)
TODO: comment.
const G & b
Definition: Group.h:83
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:60
SharedNoiseModel noiseModel_
Non-linear factor base classes.
NoiseModelFactor2< VALUE, VALUE > Base
void serialize(ARCHIVE &ar, const unsigned int)
Pose3 x1
Definition: testPose3.cpp:588
const Symbol key2('v', 2)
float * p
NonlinearEquality2< VALUE > This
#define GTSAM_CONCEPT_MANIFOLD_TYPE(T)
Definition: Manifold.h:181
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
NonlinearEquality< VALUE > This
const G double tol
Definition: Group.h:83
double error(const Values &c) const override
Vector evaluateError(const X &x1, const X &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
NonlinearEquality1< VALUE > This
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 x
#define abs(x)
Definition: datatypes.h:17
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:59
std::ptrdiff_t j
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
static shared_ptr All(size_t dim)
Definition: NoiseModel.h:467


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:03