#include <Matrix.h>
Public Types | |
typedef Eigen::Matrix< double, N, N > | MatrixN |
typedef std::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={}, OptionalJacobian< N, N > H2={}) const |
f(a).inverse() * b, with optional derivatives More... | |
Static Public Attributes | |
constexpr static auto | M = traits<T>::dimension |
Private Attributes | |
const Operator | phi_ |
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 462 of file base/Matrix.h.
typedef Eigen::Matrix<double, N, N> gtsam::MultiplyWithInverseFunction< T, N >::MatrixN |
Definition at line 465 of file base/Matrix.h.
typedef std::function<VectorN( const T&, const VectorN&, OptionalJacobian<N, M>, OptionalJacobian<N, N>)> gtsam::MultiplyWithInverseFunction< T, N >::Operator |
Definition at line 471 of file base/Matrix.h.
typedef Eigen::Matrix<double, N, 1> gtsam::MultiplyWithInverseFunction< T, N >::VectorN |
Definition at line 464 of file base/Matrix.h.
|
inline |
Construct with function as explained above.
Definition at line 474 of file base/Matrix.h.
|
inline |
f(a).inverse() * b, with optional derivatives
Definition at line 477 of file base/Matrix.h.
|
inlinestaticconstexpr |
Definition at line 463 of file base/Matrix.h.
|
private |
Definition at line 495 of file base/Matrix.h.