#include <Expression.h>

Classes | |
| struct | BinaryFunction |
| struct | TernaryFunction |
| struct | UnaryFunction |
Public Types | |
| typedef Expression< T > | type |
| Define type so we can apply it as a meta-function. More... | |
Public Member Functions | |
| virtual std::shared_ptr< Expression > | clone () const |
| void | dims (std::map< Key, int > &map) const |
| Return dimensions for each argument, as a map. More... | |
| template<typename A > | |
| Expression (const Expression< A > &expression, T(A::*method)(typename MakeOptionalJacobian< T, A >::type) const) | |
| Construct a nullary method expression. More... | |
| template<typename A1 , typename A2 , typename A3 > | |
| Expression (const Expression< A1 > &expression1, T(A1::*method)(const A2 &, const A3 &, typename MakeOptionalJacobian< T, A1 >::type, typename MakeOptionalJacobian< T, A2 >::type, typename MakeOptionalJacobian< T, A3 >::type) const, const Expression< A2 > &expression2, const Expression< A3 > &expression3) | |
| Construct a binary method expression. More... | |
| template<typename A1 , typename A2 > | |
| Expression (const Expression< A1 > &expression1, T(A1::*method)(const A2 &, typename MakeOptionalJacobian< T, A1 >::type, typename MakeOptionalJacobian< T, A2 >::type) const, const Expression< A2 > &expression2) | |
| Construct a unary method expression. More... | |
| Expression (const Key &key) | |
| Construct a leaf expression, with Key. More... | |
| Expression (const Symbol &symbol) | |
| Construct a leaf expression, with Symbol. More... | |
| Expression (const T &value) | |
| Construct a constant expression. More... | |
| template<typename A1 , typename A2 > | |
| Expression (typename BinaryFunction< A1, A2 >::type function, const Expression< A1 > &expression1, const Expression< A2 > &expression2) | |
| Construct a binary function expression. More... | |
| template<typename A1 , typename A2 , typename A3 > | |
| Expression (typename TernaryFunction< A1, A2, A3 >::type function, const Expression< A1 > &expression1, const Expression< A2 > &expression2, const Expression< A3 > &expression3) | |
| Construct a ternary function expression. More... | |
| template<typename A > | |
| Expression (typename UnaryFunction< A >::type function, const Expression< A > &expression) | |
| Construct a unary function expression. More... | |
| Expression (unsigned char c, std::uint64_t j) | |
| Construct a leaf expression, creating Symbol. More... | |
| std::set< Key > | keys () const |
| Return keys that play in this expression. More... | |
| Expression< T > & | operator+= (const Expression< T > &e) |
| Add another expression to this expression. More... | |
| void | print (const std::string &s) const |
| Print. More... | |
| const std::shared_ptr< internal::ExpressionNode< T > > & | root () const |
| Return root. More... | |
| size_t | traceSize () const |
| Return size needed for memory buffer in traceExecution. More... | |
| T | value (const Values &values, std::vector< Matrix > &H) const |
| T | value (const Values &values, std::vector< Matrix > *H=nullptr) const |
| Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient, and H should have correct size. The order of the Jacobians is same as keys in either keys() or dims() More... | |
| virtual | ~Expression () |
| Destructor. More... | |
Protected Types | |
| typedef std::pair< KeyVector, FastVector< int > > | KeysAndDims |
| Keys and dimensions in same order. More... | |
Protected Member Functions | |
| Expression () | |
| Default constructor, for serialization. More... | |
| Expression (const std::shared_ptr< internal::ExpressionNode< T > > &root) | |
| Construct with a custom root. More... | |
| KeysAndDims | keysAndDims () const |
| T | traceExecution (const Values &values, internal::ExecutionTrace< T > &trace, char *traceStorage) const |
| trace execution, very unsafe More... | |
| T | valueAndDerivatives (const Values &values, const KeyVector &keys, const FastVector< int > &dims, std::vector< Matrix > &H) const |
| private version that takes keys and dimensions, returns derivatives More... | |
| T | valueAndJacobianMap (const Values &values, internal::JacobianMap &jacobians) const |
| brief Return value and derivatives, reverse AD version More... | |
Protected Attributes | |
| std::shared_ptr< internal::ExpressionNode< T > > | root_ |
Friends | |
| class | ::ExpressionFactorShallowTest |
| class | ExpressionEqualityConstraint< T > |
| class | ExpressionFactor< T > |
| class | internal::ExpressionNode< T > |
| class | ScalarExpressionInequalityConstraint |
Expression class that supports automatic differentiation
Definition at line 49 of file Expression.h.
|
protected |
Keys and dimensions in same order.
Definition at line 193 of file Expression.h.
| typedef Expression<T> gtsam::Expression< T >::type |
Define type so we can apply it as a meta-function.
Definition at line 54 of file Expression.h.
|
inlineprotected |
Construct with a custom root.
Definition at line 62 of file Expression.h.
| gtsam::Expression< T >::Expression | ( | const T & | value | ) |
Construct a constant expression.
Definition at line 35 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | const Key & | key | ) |
Construct a leaf expression, with Key.
Definition at line 40 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | const Symbol & | symbol | ) |
Construct a leaf expression, with Symbol.
Definition at line 45 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | unsigned char | c, |
| std::uint64_t | j | ||
| ) |
Construct a leaf expression, creating Symbol.
Definition at line 50 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | typename UnaryFunction< A >::type | function, |
| const Expression< A > & | expression | ||
| ) |
Construct a unary function expression.
Definition at line 57 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | typename BinaryFunction< A1, A2 >::type | function, |
| const Expression< A1 > & | expression1, | ||
| const Expression< A2 > & | expression2 | ||
| ) |
Construct a binary function expression.
Definition at line 65 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | typename TernaryFunction< A1, A2, A3 >::type | function, |
| const Expression< A1 > & | expression1, | ||
| const Expression< A2 > & | expression2, | ||
| const Expression< A3 > & | expression3 | ||
| ) |
Construct a ternary function expression.
Definition at line 75 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | const Expression< A > & | expression, |
| T(A::*)(typename MakeOptionalJacobian< T, A >::type) const | method | ||
| ) |
Construct a nullary method expression.
Definition at line 86 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | const Expression< A1 > & | expression1, |
| T(A1::*)(const A2 &, typename MakeOptionalJacobian< T, A1 >::type, typename MakeOptionalJacobian< T, A2 >::type) const | method, | ||
| const Expression< A2 > & | expression2 | ||
| ) |
Construct a unary method expression.
Definition at line 97 of file Expression-inl.h.
| gtsam::Expression< T >::Expression | ( | const Expression< A1 > & | expression1, |
| T(A1::*)(const A2 &, const A3 &, typename MakeOptionalJacobian< T, A1 >::type, typename MakeOptionalJacobian< T, A2 >::type, typename MakeOptionalJacobian< T, A3 >::type) const | method, | ||
| const Expression< A2 > & | expression2, | ||
| const Expression< A3 > & | expression3 | ||
| ) |
Construct a binary method expression.
Definition at line 112 of file Expression-inl.h.
|
inlinevirtual |
Destructor.
Definition at line 142 of file Expression.h.
|
inlineprotected |
Default constructor, for serialization.
Definition at line 190 of file Expression.h.
|
inlinevirtual |
Definition at line 174 of file Expression.h.
| void gtsam::Expression< T >::dims | ( | std::map< Key, int > & | map | ) | const |
Return dimensions for each argument, as a map.
Definition at line 133 of file Expression-inl.h.
| std::set< Key > gtsam::Expression< T >::keys |
Return keys that play in this expression.
Definition at line 128 of file Expression-inl.h.
|
protected |
Definition at line 229 of file Expression-inl.h.
| Expression< T > & gtsam::Expression< T >::operator+= | ( | const Expression< T > & | e | ) |
Add another expression to this expression.
Definition at line 302 of file Expression-inl.h.
| void gtsam::Expression< T >::print | ( | const std::string & | s | ) | const |
Print.
Definition at line 138 of file Expression-inl.h.
| const std::shared_ptr< internal::ExpressionNode< T > > & gtsam::Expression< T >::root |
Return root.
Definition at line 156 of file Expression-inl.h.
|
protected |
trace execution, very unsafe
Definition at line 192 of file Expression-inl.h.
| size_t gtsam::Expression< T >::traceSize |
Return size needed for memory buffer in traceExecution.
Definition at line 161 of file Expression-inl.h.
|
inline |
An overload of the value function to accept reference to vector of matrices instead of a pointer to vector of matrices.
Definition at line 165 of file Expression.h.
| T gtsam::Expression< T >::value | ( | const Values & | values, |
| std::vector< Matrix > * | H = nullptr |
||
| ) | const |
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient, and H should have correct size. The order of the Jacobians is same as keys in either keys() or dims()
Definition at line 143 of file Expression-inl.h.
|
protected |
private version that takes keys and dimensions, returns derivatives
Definition at line 168 of file Expression-inl.h.
|
protected |
brief Return value and derivatives, reverse AD version
Definition at line 205 of file Expression-inl.h.
|
friend |
Definition at line 215 of file Expression.h.
|
friend |
Definition at line 211 of file Expression.h.
|
friend |
Definition at line 209 of file Expression.h.
|
friend |
Definition at line 210 of file Expression.h.
|
friend |
Definition at line 212 of file Expression.h.
|
protected |
Definition at line 59 of file Expression.h.