ExpressionFactorGraph.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 
23 
24 namespace gtsam {
25 
30 
31 public:
32 
35 
42  template<typename T>
43  void addExpressionFactor(const Expression<T>& h, const T& z,
44  const SharedNoiseModel& R) {
45  using F = ExpressionFactor<T>;
46  push_back(std::allocate_shared<F>(Eigen::aligned_allocator<F>(), R, z, h));
47  }
48 
50 };
51 
52 }
gtsam::ExpressionFactorGraph::addExpressionFactor
void addExpressionFactor(const Expression< T > &h, const T &z, const SharedNoiseModel &R)
Definition: ExpressionFactorGraph.h:43
gtsam::ExpressionFactorGraph
Definition: ExpressionFactorGraph.h:29
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::Expression
Definition: Expression.h:47
Eigen::aligned_allocator
STL compatible allocator to use with types requiring a non standrad alignment.
Definition: Memory.h:878
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
Eigen::Triplet< double >
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
gtsam
traits
Definition: chartTesting.h:28
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::FactorGraph< NonlinearFactor >::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
ExpressionFactor.h
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::ExpressionFactor
Definition: Expression.h:36


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