NonlinearInequalityConstraint.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 
19 #pragma once
20 
24 
25 namespace gtsam {
26 
31  public:
34  typedef std::shared_ptr<This> shared_ptr;
35 
37  using Base::Base;
38 
41 
43  virtual Vector unwhitenedExpr(const Values& x, OptionalMatrixVecType H = nullptr) const = 0;
44 
45  virtual Vector whitenedExpr(const Values& x) const;
46 
48  virtual Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = nullptr) const override;
49 
51  virtual bool active(const Values& x) const override;
52 
54  virtual NonlinearEqualityConstraint::shared_ptr createEqualityConstraint() const;
55 
57  virtual NoiseModelFactor::shared_ptr penaltyFactorCustom(
58  InequalityPenaltyFunction::shared_ptr func, const double mu = 1.0) const;
59 
61  virtual NoiseModelFactor::shared_ptr penaltyFactorEquality(const double mu = 1.0) const;
62 
63  private:
64 #if GTSAM_ENABLE_BOOST_SERIALIZATION
65 
66  friend class boost::serialization::access;
67  template <class ARCHIVE>
68  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
69  ar& boost::serialization::make_nvp("NonlinearInequalityConstraint",
70  boost::serialization::base_object<Base>(*this));
71  }
72 #endif
73 };
74 
79  public:
82  typedef std::shared_ptr<This> shared_ptr;
83 
84  protected:
87 
88  public:
95  ScalarExpressionInequalityConstraint(const Double_& expression, const double& sigma);
96 
99  static ScalarExpressionInequalityConstraint::shared_ptr GeqZero(const Double_& expression,
100  const double& sigma);
101 
103  static ScalarExpressionInequalityConstraint::shared_ptr LeqZero(const Double_& expression,
104  const double& sigma);
105 
107  virtual Vector unwhitenedExpr(const Values& x, OptionalMatrixVecType H = nullptr) const override;
108 
110  NonlinearEqualityConstraint::shared_ptr createEqualityConstraint() const override;
111 
113  NoiseModelFactor::shared_ptr penaltyFactor(const double mu = 1.0) const override;
114 
117  const double mu = 1.0) const override;
118 
120  virtual NoiseModelFactor::shared_ptr penaltyFactorEquality(const double mu = 1.0) const override;
121 
123  const Double_& expression() const { return expression_; }
124 
127  return std::static_pointer_cast<gtsam::NonlinearFactor>(
129  }
130 
131  private:
132 #if GTSAM_ENABLE_BOOST_SERIALIZATION
133 
134  friend class boost::serialization::access;
135  template <class ARCHIVE>
136  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
137  ar& boost::serialization::make_nvp("ExpressionEqualityConstraint",
138  boost::serialization::base_object<Base>(*this));
139  ar& BOOST_SERIALIZATION_NVP(expression_);
140  ar& BOOST_SERIALIZATION_NVP(dims_);
141  }
142 #endif
143 };
144 
147  : public FactorGraph<NonlinearInequalityConstraint> {
148  public:
151  typedef std::shared_ptr<This> shared_ptr;
152 
153  using Base::Base;
154 
156  size_t dim() const;
157 
159  Vector violationVector(const Values& values, bool whiten = true) const;
160 
162  double violationNorm(const Values& values) const;
163 
165  NonlinearFactorGraph penaltyGraph(const double mu = 1.0) const;
166 
169  const double mu = 1.0) const;
170 
171  private:
172 #if GTSAM_ENABLE_BOOST_SERIALIZATION
173 
174  friend class boost::serialization::access;
175  template <class ARCHIVE>
176  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
177  ar& boost::serialization::make_nvp("NonlinearInequalityConstraints",
178  boost::serialization::base_object<Base>(*this));
179  }
180 #endif
181 };
182 
183 } // namespace gtsam
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::ScalarExpressionInequalityConstraint::expression
const Double_ & expression() const
Definition: NonlinearInequalityConstraint.h:123
gtsam::ScalarExpressionInequalityConstraint::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearInequalityConstraint.h:82
gtsam::NonlinearInequalityConstraints::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearInequalityConstraint.h:151
mu
double mu
Definition: testBoundingConstraint.cpp:37
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
gtsam::ScalarExpressionInequalityConstraint::This
ScalarExpressionInequalityConstraint This
Definition: NonlinearInequalityConstraint.h:81
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
NonlinearEqualityConstraint.h
Nonlinear equality constraints in constrained optimization.
gtsam::ScalarExpressionInequalityConstraint::expression_
Double_ expression_
Definition: NonlinearInequalityConstraint.h:85
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:247
gtsam::NoiseModelFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:210
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::ScalarExpressionInequalityConstraint
Definition: NonlinearInequalityConstraint.h:78
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:170
gtsam::FactorGraph
Definition: BayesTree.h:34
gtsam::ScalarExpressionInequalityConstraint::dims_
FastVector< int > dims_
Definition: NonlinearInequalityConstraint.h:86
gtsam::Expression< double >
gtsam::NonlinearInequalityConstraint::Base
NonlinearConstraint Base
Definition: NonlinearInequalityConstraint.h:32
expressions.h
Common expressions, both linear and non-linear.
gtsam::NonlinearInequalityConstraints::Base
FactorGraph< NonlinearInequalityConstraint > Base
Definition: NonlinearInequalityConstraint.h:149
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::NonlinearInequalityConstraint::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearInequalityConstraint.h:34
gtsam::ScalarExpressionInequalityConstraint::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: NonlinearInequalityConstraint.h:126
gtsam::InequalityPenaltyFunction::shared_ptr
std::shared_ptr< InequalityPenaltyFunction > shared_ptr
Definition: InequalityPenaltyFunction.h:29
gtsam::NonlinearInequalityConstraint::~NonlinearInequalityConstraint
virtual ~NonlinearInequalityConstraint()
Definition: NonlinearInequalityConstraint.h:40
gtsam::NonlinearInequalityConstraints
Container of NonlinearInequalityConstraint.
Definition: NonlinearInequalityConstraint.h:146
gtsam::OptionalMatrixVecType
std::vector< Matrix > * OptionalMatrixVecType
Definition: NonlinearFactor.h:62
gtsam::NonlinearInequalityConstraint
Definition: NonlinearInequalityConstraint.h:30
gtsam
traits
Definition: SFMdata.h:40
gtsam::Values
Definition: Values.h:65
Base::Base
Base()=default
This
#define This
Definition: ActiveSetSolver-inl.h:27
gtsam::NonlinearInequalityConstraints::This
NonlinearInequalityConstraints This
Definition: NonlinearInequalityConstraint.h:150
gtsam::ScalarExpressionInequalityConstraint::Base
NonlinearInequalityConstraint Base
Definition: NonlinearInequalityConstraint.h:80
gtsam::NonlinearConstraint
Definition: NonlinearConstraint.h:36
func
Definition: benchGeometry.cpp:23
gtsam::NonlinearInequalityConstraint::This
NonlinearInequalityConstraint This
Definition: NonlinearInequalityConstraint.h:33
InequalityPenaltyFunction.h
Ramp function to compute inequality constraint violations.
gtsam::NonlinearEqualityConstraint::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearEqualityConstraint.h:33


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