LinearInequality.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 
20 #pragma once
21 
24 
25 namespace gtsam {
26 
27 typedef Eigen::RowVectorXd RowVector;
28 
34 public:
36  typedef JacobianFactor Base;
37  typedef boost::shared_ptr<This> shared_ptr;
38 
39 private:
41  bool active_;
42 
43 public:
46  Base(), active_(true) {
47  }
48 
50  explicit LinearInequality(const HessianFactor& hf) {
51  throw std::runtime_error(
52  "Cannot convert HessianFactor to LinearInequality");
53  }
54 
56  explicit LinearInequality(const JacobianFactor& jf, Key dualKey) :
57  Base(jf), dualKey_(dualKey), active_(true) {
58  if (!jf.isConstrained()) {
59  throw std::runtime_error(
60  "Cannot convert an unconstrained JacobianFactor to LinearInequality");
61  }
62 
63  if (jf.get_model()->dim() != 1) {
64  throw std::runtime_error("Only support single-valued inequality factor!");
65  }
66  }
67 
69  LinearInequality(Key i1, const RowVector& A1, double b, Key dualKey) :
70  Base(i1, A1, (Vector(1) << b).finished(),
71  noiseModel::Constrained::All(1)), dualKey_(dualKey), active_(true) {
72  }
73 
75  LinearInequality(Key i1, const RowVector& A1, Key i2, const RowVector& A2,
76  double b, Key dualKey) :
77  Base(i1, A1, i2, A2, (Vector(1) << b).finished(),
78  noiseModel::Constrained::All(1)), dualKey_(dualKey), active_(true) {
79  }
80 
82  LinearInequality(Key i1, const RowVector& A1, Key i2, const RowVector& A2,
83  Key i3, const RowVector& A3, double b, Key dualKey) :
84  Base(i1, A1, i2, A2, i3, A3, (Vector(1) << b).finished(),
85  noiseModel::Constrained::All(1)), dualKey_(dualKey), active_(true) {
86  }
87 
92  template<typename TERMS>
93  LinearInequality(const TERMS& terms, double b, Key dualKey) :
94  Base(terms, (Vector(1) << b).finished(), noiseModel::Constrained::All(1)), dualKey_(
95  dualKey), active_(true) {
96  }
97 
99  ~LinearInequality() override {
100  }
101 
103  bool equals(const GaussianFactor& lf, double tol = 1e-9) const override {
104  return Base::equals(lf, tol);
105  }
106 
108  void print(const std::string& s = "", const KeyFormatter& formatter =
109  DefaultKeyFormatter) const override {
110  if (active())
111  Base::print(s + " Active", formatter);
112  else
113  Base::print(s + " Inactive", formatter);
114  }
115 
118  return boost::static_pointer_cast < GaussianFactor
119  > (boost::make_shared < LinearInequality > (*this));
120  }
121 
123  Key dualKey() const {
124  return dualKey_;
125  }
126 
128  bool active() const {
129  return active_;
130  }
131 
133  void activate() {
134  active_ = true;
135  }
136 
138  void inactivate() {
139  active_ = false;
140  }
141 
144  return unweighted_error(c);
145  }
146 
148  double error(const VectorValues& c) const override {
149  return error_vector(c)[0];
150  }
151 
153  double dotProductRow(const VectorValues& p) const {
154  double aTp = 0.0;
155  for (const_iterator xj = begin(); xj != end(); ++xj) {
156  Vector pj = p.at(*xj);
157  Vector aj = getA(xj).transpose();
158  aTp += aj.dot(pj);
159  }
160  return aTp;
161  }
162 
163 };
164 // \ LinearInequality
165 
167 template<> struct traits<LinearInequality> : public Testable<LinearInequality> {
168 };
169 
170 } // \ namespace gtsam
171 
LinearInequality(Key i1, const RowVector &A1, Key i2, const RowVector &A2, double b, Key dualKey)
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
GaussianFactor::shared_ptr clone() const override
Vector unweighted_error(const VectorValues &c) const
LinearInequality(const HessianFactor &hf)
LinearInequality This
Typedef to this class.
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
constABlock getA() const
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
const_iterator end() const
Definition: Factor.h:130
Key dualKey() const
dual key
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
Vector & at(Key j)
Definition: VectorValues.h:137
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
double error(const VectorValues &c) const override
const KeyFormatter & formatter
void inactivate()
Make this inequality constraint inactive.
Factor Graph Values.
bool active() const
return true if this constraint is active
Eigen::VectorXd Vector
Definition: Vector.h:38
const_iterator begin() const
Definition: Factor.h:127
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
const G & b
Definition: Group.h:83
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
void activate()
Make this inequality constraint active.
const SharedDiagonal & get_model() const
traits
Definition: chartTesting.h:28
bool isConstrained() const
LinearInequality(const TERMS &terms, double b, Key dualKey)
float * p
LinearInequality(Key i1, const RowVector &A1, Key i2, const RowVector &A2, Key i3, const RowVector &A3, double b, Key dualKey)
A Gaussian factor using the canonical parameters (information form)
LinearInequality(const JacobianFactor &jf, Key dualKey)
Vector error_vector(const VectorValues &c) const
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
const G double tol
Definition: Group.h:83
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
LinearInequality(Key i1, const RowVector &A1, double b, Key dualKey)
double dotProductRow(const VectorValues &p) const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
JacobianFactor Base
Typedef to base class.
Eigen::RowVectorXd RowVector
Definition: LinearCost.h:25


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:31