Public Types | Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
gtsam::OptionalJacobian< Rows, Cols > Class Template Reference

#include <OptionalJacobian.h>

Public Types

typedef Eigen::Matrix< double, Rows, ColsJacobian
 

Public Member Functions

template<int N>
OptionalJacobian< Rows, Ncols (int startCol)
 
 operator bool () const
 Return true if allocated, false if default constructor was used. More...
 
Eigen::Map< Jacobian > & operator* ()
 De-reference, like boost optional. More...
 
Eigen::Map< Jacobian > * operator-> ()
 operator->() More...
 
 OptionalJacobian ()
 Default constructor acts like boost::none. More...
 
 OptionalJacobian (Jacobian &fixed)
 Constructor that will usurp data of a fixed-size matrix. More...
 
 OptionalJacobian (Jacobian *fixedPtr)
 Constructor that will usurp data of a fixed-size matrix, pointer version. More...
 
 OptionalJacobian (Eigen::MatrixXd &dynamic)
 Constructor that will resize a dynamic matrix (unless already correct) More...
 
 OptionalJacobian (boost::none_t)
 Constructor with boost::none just makes empty. More...
 
 OptionalJacobian (const boost::optional< Eigen::MatrixXd & > optional)
 Constructor compatible with old-style derivatives. More...
 

Private Member Functions

 OptionalJacobian (double *data)
 
void usurp (double *data)
 View on constructor argument, if given. More...
 

Private Attributes

Eigen::Map< Jacobianmap_
 

Friends

template<int M, int N>
class OptionalJacobian
 

Detailed Description

template<int Rows, int Cols>
class gtsam::OptionalJacobian< Rows, Cols >

OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size or dynamic Eigen matrix. In the latter case, the dynamic matrix will be resized. Finally, there is a constructor that takes boost::none, the default constructor acts like boost::none, and boost::optional<Eigen::MatrixXd&> is also supported for backwards compatibility. Below this class, a dynamic version is also implemented.

Definition at line 39 of file OptionalJacobian.h.

Member Typedef Documentation

template<int Rows, int Cols>
typedef Eigen::Matrix<double, Rows, Cols> gtsam::OptionalJacobian< Rows, Cols >::Jacobian

Jacobian size type TODO(frank): how to enforce RowMajor? Or better, make it work with any storage order?

Definition at line 45 of file OptionalJacobian.h.

Constructor & Destructor Documentation

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( double *  data)
inlineprivate

Definition at line 58 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( )
inline

Default constructor acts like boost::none.

Definition at line 68 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( Jacobian fixed)
inline

Constructor that will usurp data of a fixed-size matrix.

Definition at line 73 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( Jacobian fixedPtr)
inline

Constructor that will usurp data of a fixed-size matrix, pointer version.

Definition at line 79 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( Eigen::MatrixXd &  dynamic)
inline

Constructor that will resize a dynamic matrix (unless already correct)

Definition at line 86 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( boost::none_t  )
inline

Constructor with boost::none just makes empty.

Definition at line 95 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::OptionalJacobian ( const boost::optional< Eigen::MatrixXd & >  optional)
inline

Constructor compatible with old-style derivatives.

Definition at line 100 of file OptionalJacobian.h.

Member Function Documentation

template<int Rows, int Cols>
template<int N>
OptionalJacobian<Rows, N> gtsam::OptionalJacobian< Rows, Cols >::cols ( int  startCol)
inline

Access M*N sub-block if we are allocated, otherwise none TODO(frank): this could work as is below if only constructor above worked Access Rows*N sub-block if we are allocated, otherwise return an empty OptionalJacobian The use case is functions with arguments that are dissected, e.g. Pose3 into Rot3, Point3 TODO(frank): ideally, we'd like full block functionality, but see note above.

Definition at line 144 of file OptionalJacobian.h.

template<int Rows, int Cols>
gtsam::OptionalJacobian< Rows, Cols >::operator bool ( ) const
inline

Return true if allocated, false if default constructor was used.

Constructor that will usurp data of a block expression TODO(frank): unfortunately using a Map makes usurping non-contiguous memory impossible

Definition at line 116 of file OptionalJacobian.h.

template<int Rows, int Cols>
Eigen::Map<Jacobian>& gtsam::OptionalJacobian< Rows, Cols >::operator* ( )
inline

De-reference, like boost optional.

Definition at line 121 of file OptionalJacobian.h.

template<int Rows, int Cols>
Eigen::Map<Jacobian>* gtsam::OptionalJacobian< Rows, Cols >::operator-> ( )
inline

operator->()

Definition at line 126 of file OptionalJacobian.h.

template<int Rows, int Cols>
void gtsam::OptionalJacobian< Rows, Cols >::usurp ( double *  data)
inlineprivate

View on constructor argument, if given.

Definition at line 53 of file OptionalJacobian.h.

Friends And Related Function Documentation

template<int Rows, int Cols>
template<int M, int N>
friend class OptionalJacobian
friend

Definition at line 63 of file OptionalJacobian.h.

Member Data Documentation

template<int Rows, int Cols>
Eigen::Map<Jacobian> gtsam::OptionalJacobian< Rows, Cols >::map_
private

Definition at line 49 of file OptionalJacobian.h.


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


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