Public Types | Public Member Functions | Private Attributes | List of all members
gtsam::MultiplyWithInverseFunction< T, N > Struct Template Reference

#include <Matrix.h>

Public Types

enum  { M = traits<T>::dimension }
 
typedef Eigen::Matrix< double, N, NMatrixN
 
typedef boost::function< VectorN(const T &, const VectorN &, OptionalJacobian< N, M >, OptionalJacobian< N, N >)> Operator
 
typedef Eigen::Matrix< double, N, 1 > VectorN
 

Public Member Functions

 MultiplyWithInverseFunction (const Operator &phi)
 Construct with function as explained above. More...
 
VectorN operator() (const T &a, const VectorN &b, OptionalJacobian< N, M > H1=boost::none, OptionalJacobian< N, N > H2=boost::none) const
 f(a).inverse() * b, with optional derivatives More...
 

Private Attributes

const Operator phi_
 

Detailed Description

template<typename T, int N>
struct gtsam::MultiplyWithInverseFunction< T, N >

Functor that implements multiplication with the inverse of a matrix, itself the result of a function f. It turn out we only need the derivatives of the operator phi(a): b -> f(a) * b

Definition at line 485 of file base/Matrix.h.

Member Typedef Documentation

template<typename T , int N>
typedef Eigen::Matrix<double, N, N> gtsam::MultiplyWithInverseFunction< T, N >::MatrixN

Definition at line 488 of file base/Matrix.h.

template<typename T , int N>
typedef boost::function<VectorN( const T&, const VectorN&, OptionalJacobian<N, M>, OptionalJacobian<N, N>)> gtsam::MultiplyWithInverseFunction< T, N >::Operator

Definition at line 494 of file base/Matrix.h.

template<typename T , int N>
typedef Eigen::Matrix<double, N, 1> gtsam::MultiplyWithInverseFunction< T, N >::VectorN

Definition at line 487 of file base/Matrix.h.

Member Enumeration Documentation

template<typename T , int N>
anonymous enum
Enumerator

Definition at line 486 of file base/Matrix.h.

Constructor & Destructor Documentation

template<typename T , int N>
gtsam::MultiplyWithInverseFunction< T, N >::MultiplyWithInverseFunction ( const Operator phi)
inline

Construct with function as explained above.

Definition at line 497 of file base/Matrix.h.

Member Function Documentation

template<typename T , int N>
VectorN gtsam::MultiplyWithInverseFunction< T, N >::operator() ( const T a,
const VectorN b,
OptionalJacobian< N, M H1 = boost::none,
OptionalJacobian< N, N H2 = boost::none 
) const
inline

f(a).inverse() * b, with optional derivatives

Definition at line 500 of file base/Matrix.h.

Member Data Documentation

template<typename T , int N>
const Operator gtsam::MultiplyWithInverseFunction< T, N >::phi_
private

Definition at line 518 of file base/Matrix.h.


The documentation for this struct was generated from the following file:


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