BoundingConstraint.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 
20 #include <gtsam/base/Lie.h>
22 
23 namespace gtsam {
24 
32 template<class VALUE>
33 struct BoundingConstraint1: public NoiseModelFactorN<VALUE> {
34  typedef VALUE X;
36  typedef std::shared_ptr<BoundingConstraint1<VALUE> > shared_ptr;
37 
38  // Provide access to the Matrix& version of evaluateError:
39  using Base::evaluateError;
40 
41  double threshold_;
43 
45  bool isGreaterThan, double mu = 1000.0) :
46  Base(noiseModel::Constrained::All(1, mu), key),
47  threshold_(threshold), isGreaterThan_(isGreaterThan) {
48  }
49 
50  ~BoundingConstraint1() override {}
51 
52  inline double threshold() const { return threshold_; }
53  inline bool isGreaterThan() const { return isGreaterThan_; }
54 
60  virtual double value(const X& x, OptionalMatrixType H =
61  OptionalNone) const = 0;
62 
64  bool active(const Values& c) const override {
65  // note: still active at equality to avoid zigzagging
66  double x = value(c.at<X>(this->key()));
67  return (isGreaterThan_) ? x <= threshold_ : x >= threshold_;
68  }
69 
70  Vector evaluateError(const X& x, OptionalMatrixType H) const override {
71  Matrix D;
72  double error = value(x, &D) - threshold_;
73  if (H) {
74  if (isGreaterThan_) *H = D;
75  else *H = -1.0 * D;
76  }
77 
78  if (isGreaterThan_)
79  return (Vector(1) << error).finished();
80  else
81  return -1.0 * (Vector(1) << error).finished();
82  }
83 
84 private:
85 
86 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
87 
88  friend class boost::serialization::access;
89  template<class ARCHIVE>
90  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
91  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
92  ar & boost::serialization::make_nvp("NoiseModelFactor1",
93  boost::serialization::base_object<Base>(*this));
94  ar & BOOST_SERIALIZATION_NVP(threshold_);
95  ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);
96  }
97 #endif
98 };
99 
104 template<class VALUE1, class VALUE2>
105 struct BoundingConstraint2: public NoiseModelFactorN<VALUE1, VALUE2> {
106  typedef VALUE1 X1;
107  typedef VALUE2 X2;
108 
110  typedef std::shared_ptr<BoundingConstraint2<VALUE1, VALUE2> > shared_ptr;
111 
112  // Provide access to the Matrix& version of evaluateError:
113  using Base::evaluateError;
114 
115  double threshold_;
117 
119  bool isGreaterThan, double mu = 1000.0)
120  : Base(noiseModel::Constrained::All(1, mu), key1, key2),
121  threshold_(threshold), isGreaterThan_(isGreaterThan) {}
122 
123  ~BoundingConstraint2() override {}
124 
125  inline double threshold() const { return threshold_; }
126  inline bool isGreaterThan() const { return isGreaterThan_; }
127 
132  virtual double value(const X1& x1, const X2& x2,
134  OptionalMatrixType H2 = OptionalNone) const = 0;
135 
137  bool active(const Values& c) const override {
138  // note: still active at equality to avoid zigzagging
139  double x = value(c.at<X1>(this->key1()), c.at<X2>(this->key2()));
140  return (isGreaterThan_) ? x <= threshold_ : x >= threshold_;
141  }
142 
143  Vector evaluateError(const X1& x1, const X2& x2,
144  OptionalMatrixType H1, OptionalMatrixType H2) const override {
145  Matrix D1, D2;
146  double error = value(x1, x2, &D1, &D2) - threshold_;
147  if (H1) {
148  if (isGreaterThan_) *H1 = D1;
149  else *H1 = -1.0 * D1;
150  }
151  if (H2) {
152  if (isGreaterThan_) *H2 = D2;
153  else *H2 = -1.0 * D2;
154  }
155 
156  if (isGreaterThan_)
157  return (Vector(1) << error).finished();
158  else
159  return -1.0 * (Vector(1) << error).finished();
160  }
161 
162 private:
163 
164 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
165 
166  friend class boost::serialization::access;
167  template<class ARCHIVE>
168  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
169  // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
170  ar & boost::serialization::make_nvp("NoiseModelFactor2",
171  boost::serialization::base_object<Base>(*this));
172  ar & BOOST_SERIALIZATION_NVP(threshold_);
173  ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);
174  }
175 #endif
176 };
177 
178 } // \namespace gtsam
std::string serialize(const T &input)
serializes to a string
const ValueType at(Key j) const
Definition: Values-inl.h:204
BoundingConstraint1(Key key, double threshold, bool isGreaterThan, double mu=1000.0)
flag for greater/less than
double mu
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
NoiseModelFactorN< VALUE1, VALUE2 > Base
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
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
bool active(const Values &c) const override
#define OptionalNone
const SharedNoiseModel & noiseModel() const
access to the noise model
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
NoiseModelFactorN< VALUE > Base
std::shared_ptr< BoundingConstraint2< VALUE1, VALUE2 > > shared_ptr
Base class and basic functions for Lie types.
BoundingConstraint2(Key key1, Key key2, double threshold, bool isGreaterThan, double mu=1000.0)
flag for greater/less than
Vector evaluateError(const X &x, OptionalMatrixType H) const override
traits
Definition: chartTesting.h:28
virtual double value(const X &x, OptionalMatrixType H=OptionalNone) const =0
double error(const Values &c) const override
Non-linear factor base classes.
Pose3 x1
Definition: testPose3.cpp:663
bool active(const Values &c) const override
std::shared_ptr< BoundingConstraint1< VALUE > > shared_ptr
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Vector evaluateError(const X1 &x1, const X2 &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:33:59