LinearCost.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 
22 
23 namespace gtsam {
24 
25 typedef Eigen::RowVectorXd RowVector;
26 
31 class LinearCost: public JacobianFactor {
32 public:
33  typedef LinearCost This;
34  typedef JacobianFactor Base;
35  typedef boost::shared_ptr<This> shared_ptr;
36 
37 public:
40  Base() {
41  }
42 
44  explicit LinearCost(const HessianFactor& hf) {
45  throw std::runtime_error("Cannot convert HessianFactor to LinearCost");
46  }
47 
49  explicit LinearCost(const JacobianFactor& jf) :
50  Base(jf) {
51  if (jf.isConstrained()) {
52  throw std::runtime_error(
53  "Cannot convert a constrained JacobianFactor to LinearCost");
54  }
55 
56  if (jf.get_model()->dim() != 1) {
57  throw std::runtime_error(
58  "Only support single-valued linear cost factor!");
59  }
60  }
61 
63  LinearCost(Key i1, const RowVector& A1) :
64  Base(i1, A1, Vector1::Zero()) {
65  }
66 
68  LinearCost(Key i1, const RowVector& A1, Key i2, const RowVector& A2, double b) :
69  Base(i1, A1, i2, A2, Vector1::Zero()) {
70  }
71 
73  LinearCost(Key i1, const RowVector& A1, Key i2, const RowVector& A2, Key i3,
74  const RowVector& A3) :
75  Base(i1, A1, i2, A2, i3, A3, Vector1::Zero()) {
76  }
77 
81  template<typename TERMS>
82  LinearCost(const TERMS& terms) :
83  Base(terms, Vector1::Zero()) {
84  }
85 
87  ~LinearCost() override {
88  }
89 
91  bool equals(const GaussianFactor& lf, double tol = 1e-9) const override {
92  return Base::equals(lf, tol);
93  }
94 
96  void print(const std::string& s = "", const KeyFormatter& formatter =
97  DefaultKeyFormatter) const override {
98  Base::print(s + " LinearCost: ", formatter);
99  }
100 
103  return boost::static_pointer_cast < GaussianFactor
104  > (boost::make_shared < LinearCost > (*this));
105  }
106 
109  return unweighted_error(c);
110  }
111 
113  double error(const VectorValues& c) const override {
114  return error_vector(c)[0];
115  }
116 };
117 // \ LinearCost
118 
120 template<> struct traits<LinearCost> : public Testable<LinearCost> {
121 };
122 
123 } // \ namespace gtsam
124 
LinearCost(const JacobianFactor &jf)
Definition: LinearCost.h:49
LinearCost(const HessianFactor &hf)
Definition: LinearCost.h:44
Vector unweighted_error(const VectorValues &c) const
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
Definition: LinearCost.h:96
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const KeyFormatter & formatter
double error(const VectorValues &c) const override
Definition: LinearCost.h:113
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
Definition: LinearCost.h:91
LinearCost(const TERMS &terms)
Definition: LinearCost.h:82
Eigen::VectorXd Vector
Definition: Vector.h:38
LinearCost This
Typedef to this class.
Definition: LinearCost.h:33
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
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: LinearCost.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
const SharedDiagonal & get_model() const
traits
Definition: chartTesting.h:28
~LinearCost() override
Definition: LinearCost.h:87
bool isConstrained() const
LinearCost(Key i1, const RowVector &A1, Key i2, const RowVector &A2, Key i3, const RowVector &A3)
Definition: LinearCost.h:73
Vector error_vector(const VectorValues &c) const
Definition: LinearCost.h:108
A Gaussian factor using the canonical parameters (information form)
GaussianFactor::shared_ptr clone() const override
Definition: LinearCost.h:102
LinearCost(Key i1, const RowVector &A1)
Definition: LinearCost.h:63
LinearCost(Key i1, const RowVector &A1, Key i2, const RowVector &A2, double b)
Definition: LinearCost.h:68
JacobianFactor Base
Typedef to base class.
Definition: LinearCost.h:34
const G double tol
Definition: Group.h:83
The matrix class, also used for vectors and row-vectors.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Eigen::RowVectorXd RowVector
Definition: LinearCost.h:25


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