Public Member Functions | Private Member Functions | List of all members
gtsam::ScalarMultiplyExpression< T > Class Template Reference

#include <Expression.h>

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

Public Member Functions

 ScalarMultiplyExpression (double s, const Expression< T > &e)
 
- Public Member Functions inherited from gtsam::Expression< T >
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...
 

Private Member Functions

 BOOST_CONCEPT_ASSERT ((gtsam::IsVectorSpace< T >))
 

Additional Inherited Members

- Public Types inherited from gtsam::Expression< T >
typedef Expression< Ttype
 Define type so we can apply it as a meta-function. More...
 
- Protected Types inherited from gtsam::Expression< T >
typedef std::pair< KeyVector, FastVector< int > > KeysAndDims
 Keys and dimensions in same order. More...
 
- Protected Member Functions inherited from gtsam::Expression< T >
 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 inherited from gtsam::Expression< T >
boost::shared_ptr< internal::ExpressionNode< T > > root_
 

Detailed Description

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

A ScalarMultiplyExpression is a specialization of Expression that multiplies with a scalar It optimizes the Jacobian calculation for this specific case

Definition at line 214 of file Expression.h.

Constructor & Destructor Documentation

template<typename T >
gtsam::ScalarMultiplyExpression< T >::ScalarMultiplyExpression ( double  s,
const Expression< T > &  e 
)
explicit

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

Member Function Documentation

template<typename T>
gtsam::ScalarMultiplyExpression< T >::BOOST_CONCEPT_ASSERT ( (gtsam::IsVectorSpace< T >)  )
private

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


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