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 
22 #include <gtsam/base/Testable.h>
23 #include <gtsam/base/Manifold.h>
24 
25 #include <limits>
26 #include <iostream>
27 #include <cmath>
28 
29 namespace gtsam {
30 
43 template<class VALUE>
45 
46 public:
47  typedef VALUE T;
48 
49 private:
50 
51  // feasible value
53 
54  // error handling flag
56 
57  // error gain in allow error case
58  double error_gain_;
59 
60  // typedef to this class
62 
63  // typedef to base class
65 
66 public:
67 
69  using CompareFunction = std::function<bool(const T&, const T&)>;
71 
74  }
75 
76  ~NonlinearEquality() override {
77  }
78 
81 
86  const CompareFunction &_compare = std::bind(traits<T>::Equals,
87  std::placeholders::_1, std::placeholders::_2, 1e-9)) :
88  Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
90  compare_(_compare) {
91  }
92 
96  NonlinearEquality(Key j, const T& feasible, double error_gain,
97  const CompareFunction &_compare = std::bind(traits<T>::Equals,
98  std::placeholders::_1, std::placeholders::_2, 1e-9)) :
99  Base(noiseModel::Constrained::All(traits<T>::GetDimension(feasible)),
100  KeyVector{j}), feasible_(feasible), allow_error_(true), error_gain_(error_gain), //
101  compare_(_compare) {
102  }
103 
104  Key key() const {
105  return keys().front();
106  }
107 
111 
112  void print(const std::string& s = "",
113  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
114  std::cout << (s.empty() ? s : s + " ") << "Constraint: on ["
115  << keyFormatter(this->key()) << "]\n";
116  traits<VALUE>::Print(feasible_, "Feasible Point:\n");
117  std::cout << "Variable Dimension: " << traits<T>::GetDimension(feasible_)
118  << std::endl;
119  }
120 
122  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
123  const This* e = dynamic_cast<const This*>(&f);
124  return e && Base::equals(f) && traits<T>::Equals(feasible_,e->feasible_, tol)
125  && std::abs(error_gain_ - e->error_gain_) < tol;
126  }
127 
131 
133  double error(const Values& c) const override {
134  const T& xj = c.at<T>(this->key());
135  Vector e = this->unwhitenedError(c);
136  if (allow_error_ || !compare_(xj, feasible_)) {
137  return error_gain_ * dot(e, e);
138  } else {
139  return 0.0;
140  }
141  }
142 
144  Vector evaluateError(const T& xj, OptionalMatrixType H = nullptr) const {
145  const size_t nj = traits<T>::GetDimension(feasible_);
146  if (allow_error_) {
147  if (H)
148  *H = Matrix::Identity(nj,nj); // FIXME: this is not the right linearization for nonlinear compare
149  return traits<T>::Local(xj,feasible_);
150  } else if (compare_(feasible_, xj)) {
151  if (H)
152  *H = Matrix::Identity(nj,nj);
153  return Vector::Zero(nj); // set error to zero if equal
154  } else {
155  if (H)
156  throw std::invalid_argument(
157  "Linearization point not feasible for "
158  + DefaultKeyFormatter(this->key()) + "!");
159  return Vector::Constant(nj, std::numeric_limits<double>::infinity()); // set error to infinity if not equal
160  }
161  }
162 
163  Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = nullptr) const override {
164  VALUE x1 = x.at<VALUE>(key());
165  if (H) {
166  return evaluateError(x1, &(H->front()));
167  } else {
168  return evaluateError(x1);
169  }
170  }
171 
173  GaussianFactor::shared_ptr linearize(const Values& x) const override {
174  const T& xj = x.at<T>(this->key());
175  Matrix A;
176  Vector b = evaluateError(xj, &A);
179  new JacobianFactor(this->key(), A, b, model));
180  }
181 
184  return std::static_pointer_cast<gtsam::NonlinearFactor>(
186  }
187 
189 
191 
192 private:
193 
194 #if GTSAM_ENABLE_BOOST_SERIALIZATION
195  friend class boost::serialization::access;
197  template<class ARCHIVE>
198  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
199  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
200  ar
201  & boost::serialization::make_nvp("NoiseModelFactor1",
202  boost::serialization::base_object<Base>(*this));
203  ar & BOOST_SERIALIZATION_NVP(feasible_);
204  ar & BOOST_SERIALIZATION_NVP(allow_error_);
205  ar & BOOST_SERIALIZATION_NVP(error_gain_);
206  }
207 #endif
208 
209 };
210 // \class NonlinearEquality
211 
212 template <typename VALUE>
213 struct traits<NonlinearEquality<VALUE>> : Testable<NonlinearEquality<VALUE>> {};
214 
215 /* ************************************************************************* */
219 template<class VALUE>
221 
222 public:
223  typedef VALUE X;
224 
225 protected:
228 
231  }
232 
234 
237 
238 public:
239 
240  typedef std::shared_ptr<NonlinearEquality1<VALUE> > shared_ptr;
241 
248  NonlinearEquality1(const X& value, Key key, double mu = 1000.0)
249  : Base(noiseModel::Constrained::All(traits<X>::GetDimension(value),
250  std::abs(mu)),
251  KeyVector{key}),
252  value_(value) {}
253 
254  ~NonlinearEquality1() override {
255  }
256 
259  return std::static_pointer_cast<gtsam::NonlinearFactor>(
261  }
262 
263  Key key() const { return keys().front(); }
264 
266  Vector evaluateError(const X& x1, OptionalMatrixType H = nullptr) const {
267  if (H)
268  (*H) = Matrix::Identity(traits<X>::GetDimension(x1),traits<X>::GetDimension(x1));
269  // manifold equivalent of h(x)-z -> log(z,h(x))
270  return traits<X>::Local(value_,x1);
271  }
272 
273  Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = nullptr) const override {
274  X x1 = x.at<X>(key());
275  if (H) {
276  return evaluateError(x1, &(H->front()));
277  } else {
278  return evaluateError(x1);
279  }
280  }
281 
283  void print(const std::string& s = "",
284  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
285  std::cout << s << ": NonlinearEquality1(" << keyFormatter(this->key())
286  << ")," << "\n";
287  this->noiseModel_->print();
288  traits<X>::Print(value_, "Value");
289  }
290 
292 
293 private:
294 
295 #if GTSAM_ENABLE_BOOST_SERIALIZATION
296  friend class boost::serialization::access;
298  template<class ARCHIVE>
299  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
300  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
301  ar
302  & boost::serialization::make_nvp("NoiseModelFactor1",
303  boost::serialization::base_object<Base>(*this));
304  ar & BOOST_SERIALIZATION_NVP(value_);
305  }
306 #endif
307 };
308 // \NonlinearEquality1
309 
310 template <typename VALUE>
312  : Testable<NonlinearEquality1<VALUE> > {};
313 
314 /* ************************************************************************* */
319 template <class T>
321  protected:
324 
326 
327 
329 
330  public:
331  typedef std::shared_ptr<NonlinearEquality2<T>> shared_ptr;
332 
333 
341  : Base(noiseModel::Constrained::All(traits<T>::dimension, std::abs(mu)),
342  KeyVector{key1, key2}) {}
343  ~NonlinearEquality2() override {}
344 
347  return std::static_pointer_cast<gtsam::NonlinearFactor>(
349  }
350 
353  const T& x1, const T& x2, OptionalMatrixType H1 = nullptr, OptionalMatrixType H2 = nullptr) const {
354  static const size_t p = traits<T>::dimension;
355  if (H1) *H1 = -Matrix::Identity(p, p);
356  if (H2) *H2 = Matrix::Identity(p, p);
357  return traits<T>::Local(x1, x2);
358  }
359 
360  Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = nullptr) const override {
361  T x1 = x.at<T>(keys().front());
362  T x2 = x.at<T>(keys().back());
363  if (H) {
364  return evaluateError(x1, x2, &(H->front()), &(H->back()));
365  } else {
366  return evaluateError(x1, x2);
367  }
368  }
369 
371 
372  private:
373 #if GTSAM_ENABLE_BOOST_SERIALIZATION
374  friend class boost::serialization::access;
376  template <class ARCHIVE>
377  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
378  // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
379  ar& boost::serialization::make_nvp(
380  "NoiseModelFactor2", boost::serialization::base_object<Base>(*this));
381  }
382 #endif
383 };
384 // \NonlinearEquality2
385 
386 template <typename VALUE>
387 struct traits<NonlinearEquality2<VALUE>> : Testable<NonlinearEquality2<VALUE>> {
388 };
389 
390 }// namespace gtsam
key1
const Symbol key1('v', 1)
gtsam::NonlinearEquality1::X
VALUE X
Definition: NonlinearEquality.h:223
gtsam::NonlinearEquality::NonlinearEquality
NonlinearEquality()
Default constructor - only for serialization.
Definition: NonlinearEquality.h:73
gtsam::NonlinearEquality::T
VALUE T
Definition: NonlinearEquality.h:47
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:79
gtsam::NonlinearEquality::compare_
CompareFunction compare_
Definition: NonlinearEquality.h:70
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Testable.h
Concept check for values that can be used in unit tests.
gtsam::NonlinearEquality::NonlinearEquality
NonlinearEquality(Key j, const T &feasible, const CompareFunction &_compare=std::bind(traits< T >::Equals, std::placeholders::_1, std::placeholders::_2, 1e-9))
Definition: NonlinearEquality.h:85
mu
double mu
Definition: testBoundingConstraint.cpp:37
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::NonlinearEquality1::Base
NonlinearEqualityConstraint Base
Definition: NonlinearEquality.h:226
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::NonlinearEquality::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: NonlinearEquality.h:183
gtsam::NonlinearEquality1::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: NonlinearEquality.h:258
gtsam::NonlinearEquality::NonlinearEquality
NonlinearEquality(Key j, const T &feasible, double error_gain, const CompareFunction &_compare=std::bind(traits< T >::Equals, std::placeholders::_1, std::placeholders::_2, 1e-9))
Definition: NonlinearEquality.h:96
gtsam::NonlinearEquality1::NonlinearEquality1
NonlinearEquality1(const X &value, Key key, double mu=1000.0)
Definition: NonlinearEquality.h:248
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
NonlinearEqualityConstraint.h
Nonlinear equality constraints in constrained optimization.
gtsam::NonlinearEquality::CompareFunction
std::function< bool(const T &, const T &)> CompareFunction
Function that compares two values.
Definition: NonlinearEquality.h:69
gtsam::NonlinearEquality::key
Key key() const
Definition: NonlinearEquality.h:104
gtsam::NonlinearEquality::unwhitenedError
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Definition: NonlinearEquality.h:163
gtsam::NonlinearEquality::feasible_
T feasible_
Definition: NonlinearEquality.h:52
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:206
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::NonlinearEquality
Definition: NonlinearEquality.h:44
gtsam::NonlinearEquality2::This
NonlinearEquality2< T > This
Definition: NonlinearEquality.h:323
gtsam::NonlinearEquality1::shared_ptr
std::shared_ptr< NonlinearEquality1< VALUE > > shared_ptr
fixed value for variable
Definition: NonlinearEquality.h:240
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::NonlinearEquality::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: NonlinearEquality.h:112
gtsam::NonlinearEquality1::unwhitenedError
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Definition: NonlinearEquality.h:273
gtsam::NonlinearEqualityConstraint
Definition: NonlinearEqualityConstraint.h:29
Eigen::internal::VALUE
@ VALUE
Definition: SpecialFunctionsImpl.h:729
gtsam::NonlinearEquality1
Definition: NonlinearEquality.h:220
gtsam::NonlinearEquality1::This
NonlinearEquality1< VALUE > This
Definition: NonlinearEquality.h:227
A
Definition: test_numpy_dtypes.cpp:300
key2
const Symbol key2('v', 2)
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
x1
Pose3 x1
Definition: testPose3.cpp:692
gtsam::NoiseModelFactor::noiseModel
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:246
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::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::NonlinearEquality::error
double error(const Values &c) const override
Actual error function calculation.
Definition: NonlinearEquality.h:133
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:196
gtsam::noiseModel::Constrained::All
static shared_ptr All(size_t dim)
Definition: NoiseModel.h:480
Manifold.h
Base class and basic functions for Manifold types.
gtsam::NonlinearEquality2::~NonlinearEquality2
~NonlinearEquality2() override
Definition: NonlinearEquality.h:343
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:82
Eigen::Triplet< double >
gtsam::NonlinearEquality2::evaluateError
Vector evaluateError(const T &x1, const T &x2, OptionalMatrixType H1=nullptr, OptionalMatrixType H2=nullptr) const
g(x) with optional derivative2
Definition: NonlinearEquality.h:352
gtsam::NonlinearEquality2
Definition: NonlinearEquality.h:320
gtsam::NonlinearEquality2::unwhitenedError
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Definition: NonlinearEquality.h:360
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::NonlinearEquality1::evaluateError
Vector evaluateError(const X &x1, OptionalMatrixType H=nullptr) const
g(x) with optional derivative
Definition: NonlinearEquality.h:266
gtsam::NonlinearEquality2::shared_ptr
std::shared_ptr< NonlinearEquality2< T > > shared_ptr
Definition: NonlinearEquality.h:331
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
NonlinearFactor.h
Non-linear factor base classes.
gtsam::OptionalMatrixVecType
std::vector< Matrix > * OptionalMatrixVecType
Definition: NonlinearFactor.h:62
gtsam::b
const G & b
Definition: Group.h:79
gtsam::NonlinearEquality1::~NonlinearEquality1
~NonlinearEquality1() override
Definition: NonlinearEquality.h:254
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::NonlinearEquality::~NonlinearEquality
~NonlinearEquality() override
Definition: NonlinearEquality.h:76
gtsam::traits
Definition: Group.h:36
gtsam::NonlinearEquality::error_gain_
double error_gain_
Definition: NonlinearEquality.h:58
gtsam::NonlinearEquality1::NonlinearEquality1
NonlinearEquality1()
Default constructor to allow for serialization.
Definition: NonlinearEquality.h:230
gtsam::NoiseModelFactor
Definition: NonlinearFactor.h:198
gtsam::NonlinearEquality2::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: NonlinearEquality.h:346
gtsam::Values
Definition: Values.h:65
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
gtsam::NonlinearEquality2::NonlinearEquality2
NonlinearEquality2(Key key1, Key key2, double mu=1e4)
Definition: NonlinearEquality.h:340
gtsam::NonlinearEquality::This
NonlinearEquality< VALUE > This
Definition: NonlinearEquality.h:61
gtsam::NonlinearEquality1::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Print.
Definition: NonlinearEquality.h:283
std
Definition: BFloat16.h:88
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
p
float * p
Definition: Tutorial_Map_using.cpp:9
GTSAM_CONCEPT_TESTABLE_TYPE
#define GTSAM_CONCEPT_TESTABLE_TYPE(T)
Definition: Testable.h:177
gtsam::NonlinearEquality2::Base
NonlinearEqualityConstraint Base
Definition: NonlinearEquality.h:322
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
gtsam::NonlinearEquality::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearEquality.h:122
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::NonlinearConstraint::feasible
virtual bool feasible(const Values &x, const double tolerance=1e-5) const
Definition: NonlinearConstraint.h:57
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:56
abs
#define abs(x)
Definition: datatypes.h:17
gtsam::NonlinearEquality::allow_error_
bool allow_error_
Definition: NonlinearEquality.h:55
gtsam::NonlinearEquality::linearize
GaussianFactor::shared_ptr linearize(const Values &x) const override
Linearize is over-written, because base linearization tries to whiten.
Definition: NonlinearEquality.h:173
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::NonlinearEquality::evaluateError
Vector evaluateError(const T &xj, OptionalMatrixType H=nullptr) const
Error function.
Definition: NonlinearEquality.h:144
GTSAM_CONCEPT_MANIFOLD_TYPE
#define GTSAM_CONCEPT_MANIFOLD_TYPE(T)
Definition: Manifold.h:178
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
test_callbacks.value
value
Definition: test_callbacks.py:162
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
gtsam::NonlinearEquality1::key
Key key() const
Definition: NonlinearEquality.h:263
gtsam::NonlinearEquality1::value_
X value_
Definition: NonlinearEquality.h:233


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:02:33