Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Friends | List of all members
gtsam::Expression< T > Class Template Reference

#include <Expression.h>

Inheritance diagram for gtsam::Expression< T >:
Inheritance graph
[legend]

Classes

struct  BinaryFunction
 
struct  TernaryFunction
 
struct  UnaryFunction
 

Public Types

typedef Expression< Ttype
 Define type so we can apply it as a meta-function. More...
 

Public Member Functions

virtual boost::shared_ptr< Expressionclone () const
 
void dims (std::map< Key, int > &map) const
 Return dimensions for each argument, as a map. More...
 
 Expression (const T &value)
 Construct a constant 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 (unsigned char c, std::uint64_t j)
 Construct a leaf expression, creating Symbol. More...
 
template<typename A >
 Expression (typename UnaryFunction< A >::type function, const Expression< A > &expression)
 Construct a unary function 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 (const Expression< A > &expression, T(A::*method)(typename MakeOptionalJacobian< T, A >::type) const)
 Construct a nullary 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...
 
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...
 
std::set< Keykeys () 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 boost::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, boost::optional< std::vector< Matrix > & > H=boost::none) 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 (const boost::shared_ptr< internal::ExpressionNode< T > > &root)
 Construct with a custom root. More...
 
 Expression ()
 Default constructor, for serialization. More...
 
KeysAndDims keysAndDims () const
 
T traceExecution (const Values &values, internal::ExecutionTrace< T > &trace, void *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

boost::shared_ptr< internal::ExpressionNode< T > > root_
 

Friends

class ::ExpressionFactorShallowTest
 
class ExpressionFactor< T >
 
class internal::ExpressionNode< T >
 

Detailed Description

template<typename T>
class gtsam::Expression< T >

Expression class that supports automatic differentiation

Definition at line 49 of file Expression.h.

Member Typedef Documentation

template<typename T>
typedef std::pair<KeyVector, FastVector<int> > gtsam::Expression< T >::KeysAndDims
protected

Keys and dimensions in same order.

Definition at line 186 of file Expression.h.

template<typename T>
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.

Constructor & Destructor Documentation

template<typename T>
gtsam::Expression< T >::Expression ( const boost::shared_ptr< internal::ExpressionNode< T > > &  root)
inlineprotected

Construct with a custom root.

Definition at line 62 of file Expression.h.

template<typename T>
gtsam::Expression< T >::Expression ( const T value)

Construct a constant expression.

Definition at line 31 of file Expression-inl.h.

template<typename T>
gtsam::Expression< T >::Expression ( const Key key)

Construct a leaf expression, with Key.

Definition at line 36 of file Expression-inl.h.

template<typename T>
gtsam::Expression< T >::Expression ( const Symbol symbol)

Construct a leaf expression, with Symbol.

Definition at line 41 of file Expression-inl.h.

template<typename T>
gtsam::Expression< T >::Expression ( unsigned char  c,
std::uint64_t  j 
)

Construct a leaf expression, creating Symbol.

Definition at line 46 of file Expression-inl.h.

template<typename T >
template<typename A >
gtsam::Expression< T >::Expression ( typename UnaryFunction< A >::type  function,
const Expression< A > &  expression 
)

Construct a unary function expression.

Definition at line 53 of file Expression-inl.h.

template<typename T >
template<typename A1 , typename A2 >
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 61 of file Expression-inl.h.

template<typename T >
template<typename A1 , typename A2 , typename A3 >
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 71 of file Expression-inl.h.

template<typename T>
template<typename A >
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 82 of file Expression-inl.h.

template<typename T>
template<typename A1 , typename A2 >
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 92 of file Expression-inl.h.

template<typename T>
template<typename A1 , typename A2 , typename A3 >
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 104 of file Expression-inl.h.

template<typename T>
virtual gtsam::Expression< T >::~Expression ( )
inlinevirtual

Destructor.

Definition at line 142 of file Expression.h.

template<typename T>
gtsam::Expression< T >::Expression ( )
inlineprotected

Default constructor, for serialization.

Definition at line 183 of file Expression.h.

Member Function Documentation

template<typename T>
virtual boost::shared_ptr<Expression> gtsam::Expression< T >::clone ( ) const
inlinevirtual
Returns
a "deep" copy of this Expression "deep" is in quotes because the ExpressionNode hierarchy is not cloned. The intent is for derived classes to be copied using only a Base pointer.

Definition at line 167 of file Expression.h.

template<typename T >
void gtsam::Expression< T >::dims ( std::map< Key, int > &  map) const

Return dimensions for each argument, as a map.

Definition at line 122 of file Expression-inl.h.

template<typename T >
std::set< Key > gtsam::Expression< T >::keys ( ) const

Return keys that play in this expression.

Definition at line 117 of file Expression-inl.h.

template<typename T >
Expression< T >::KeysAndDims gtsam::Expression< T >::keysAndDims ( ) const
protected

Definition at line 220 of file Expression-inl.h.

template<typename T>
Expression< T > & gtsam::Expression< T >::operator+= ( const Expression< T > &  e)

Add another expression to this expression.

Definition at line 274 of file Expression-inl.h.

template<typename T >
void gtsam::Expression< T >::print ( const std::string &  s) const

Print.

Definition at line 127 of file Expression-inl.h.

template<typename T >
const boost::shared_ptr< internal::ExpressionNode< T > > & gtsam::Expression< T >::root ( ) const

Return root.

Definition at line 147 of file Expression-inl.h.

template<typename T>
T gtsam::Expression< T >::traceExecution ( const Values values,
internal::ExecutionTrace< T > &  trace,
void *  traceStorage 
) const
protected

trace execution, very unsafe

Definition at line 183 of file Expression-inl.h.

template<typename T >
size_t gtsam::Expression< T >::traceSize ( ) const

Return size needed for memory buffer in traceExecution.

Definition at line 152 of file Expression-inl.h.

template<typename T >
T gtsam::Expression< T >::value ( const Values values,
boost::optional< std::vector< Matrix > & >  H = boost::none 
) 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 132 of file Expression-inl.h.

template<typename T >
T gtsam::Expression< T >::valueAndDerivatives ( const Values values,
const KeyVector keys,
const FastVector< int > &  dims,
std::vector< Matrix > &  H 
) const
protected

private version that takes keys and dimensions, returns derivatives

Definition at line 159 of file Expression-inl.h.

template<typename T >
T gtsam::Expression< T >::valueAndJacobianMap ( const Values values,
internal::JacobianMap jacobians 
) const
protected

brief Return value and derivatives, reverse AD version

Definition at line 190 of file Expression-inl.h.

Friends And Related Function Documentation

template<typename T>
friend class ::ExpressionFactorShallowTest
friend

Definition at line 206 of file Expression.h.

template<typename T>
friend class ExpressionFactor< T >
friend

Definition at line 202 of file Expression.h.

template<typename T>
friend class internal::ExpressionNode< T >
friend

Definition at line 203 of file Expression.h.

Member Data Documentation

template<typename T>
boost::shared_ptr<internal::ExpressionNode<T> > gtsam::Expression< T >::root_
protected

Definition at line 59 of file Expression.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:08