LinearContainerFactor.h
Go to the documentation of this file.
1 
10 #pragma once
11 
14 
15 #include <optional>
16 
17 namespace gtsam {
18 
19  // Forward declarations
20  class JacobianFactor;
21  class HessianFactor;
22 
29 class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor {
30 protected:
31 
33  std::optional<Values> linearizationPoint_;
34 
36  LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const std::optional<Values>& linearizationPoint);
37 
38  // Some handy typedefs
41 
42 public:
43 
44  typedef std::shared_ptr<This> shared_ptr;
45 
48 
50  LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
51 
53  LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
54 
56  LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
57 
58  // Access
59 
60  const GaussianFactor::shared_ptr& factor() const { return factor_; }
61 
62  // Testable
63 
65  void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
66 
68  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
69 
70  // NonlinearFactor
71 
80  double error(const Values& c) const override;
81 
83  size_t dim() const override;
84 
86  const std::optional<Values>& linearizationPoint() const { return linearizationPoint_; }
87 
104  GaussianFactor::shared_ptr linearize(const Values& c) const override;
105 
109  GaussianFactor::shared_ptr negateToGaussian() const;
110 
114  NonlinearFactor::shared_ptr negateToNonlinear() const;
115 
123  return NonlinearFactor::shared_ptr(new LinearContainerFactor(factor_,linearizationPoint_));
124  }
125 
132  const std::map<Key, Key>& rekey_mapping) const override;
133 
138  NonlinearFactor::shared_ptr rekey(const KeyVector& new_keys) const override;
139 
141  inline bool hasLinearizationPoint() const { return linearizationPoint_.has_value(); }
142 
146  bool isJacobian() const;
147  bool isHessian() const;
148 
150  std::shared_ptr<JacobianFactor> toJacobian() const;
151 
153  std::shared_ptr<HessianFactor> toHessian() const;
154 
159  static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph,
160  const Values& linearizationPoint = Values());
161 
162  protected:
163  void initializeLinearizationPoint(const Values& linearizationPoint);
164 
165  private:
166 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
167 
168  friend class boost::serialization::access;
169  template<class ARCHIVE>
170  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
171  ar & boost::serialization::make_nvp("NonlinearFactor",
172  boost::serialization::base_object<Base>(*this));
173  ar & BOOST_SERIALIZATION_NVP(factor_);
174  ar & BOOST_SERIALIZATION_NVP(linearizationPoint_);
175  }
176 #endif
177 
178 }; // \class LinearContainerFactor
179 
180 template<> struct traits<LinearContainerFactor> : public Testable<LinearContainerFactor> {};
181 
182 } // \namespace gtsam
183 
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
gtsam::HessianFactor
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:100
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::LinearContainerFactor::linearizationPoint
const std::optional< Values > & linearizationPoint() const
Definition: LinearContainerFactor.h:86
gtsam::LinearContainerFactor::This
LinearContainerFactor This
Definition: LinearContainerFactor.h:40
gtsam::LinearContainerFactor::clone
NonlinearFactor::shared_ptr clone() const override
Definition: LinearContainerFactor.h:122
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::LinearContainerFactor::Base
NonlinearFactor Base
Definition: LinearContainerFactor.h:39
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::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::LinearContainerFactor::factor_
GaussianFactor::shared_ptr factor_
Definition: LinearContainerFactor.h:32
gtsam::equals
Definition: Testable.h:112
std_optional_serialization.h
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::LinearContainerFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: LinearContainerFactor.h:44
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
error
static double error
Definition: testRot3.cpp:37
gtsam::traits
Definition: Group.h:36
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
JacobianFactor
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::LinearContainerFactor
Definition: LinearContainerFactor.h:29
gtsam::LinearContainerFactor::hasLinearizationPoint
bool hasLinearizationPoint() const
Casting syntactic sugar.
Definition: LinearContainerFactor.h:141
gtsam::LinearContainerFactor::LinearContainerFactor
LinearContainerFactor()
Definition: LinearContainerFactor.h:47
gtsam::LinearContainerFactor::linearizationPoint_
std::optional< Values > linearizationPoint_
Definition: LinearContainerFactor.h:33
gtsam::LinearContainerFactor::factor
const GaussianFactor::shared_ptr & factor() const
Definition: LinearContainerFactor.h:60


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:03:00