21 #include <gtsam/config.h> 22 #include <Eigen/Dense> 24 #ifndef OPTIONALJACOBIAN_NOBOOST 25 #include <boost/optional.hpp> 38 template<
int Rows,
int Cols>
59 if (data)
usurp(data);
62 template<
int M,
int N>
88 dynamic.resize(Rows,
Cols);
89 usurp(dynamic.data());
92 #ifndef OPTIONALJACOBIAN_NOBOOST 103 optional->resize(Rows,
Cols);
104 usurp(optional->data());
116 operator bool()
const {
117 return map_.data() !=
nullptr;
185 #ifndef OPTIONALJACOBIAN_NOBOOST 195 if (optional) pointer_ = &(*optional);
201 operator bool()
const {
202 return pointer_!=
nullptr;
215 template <
typename T>
struct traits;
222 template <
class T,
class A>
233 template<
class T,
class A>
void usurp(double *data)
View on constructor argument, if given.
OptionalJacobian< traits< T >::dimension, traits< A >::dimension > type
OptionalJacobian(double *data)
A matrix or vector expression mapping an existing array of data.
: meta-function to generate Jacobian
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
Namespace containing all symbols from the Eigen library.
OptionalJacobian(boost::none_t)
Constructor with boost::none just makes empty.
OptionalJacobian< Rows, N > cols(int startCol)
OptionalJacobian(const boost::optional< Eigen::MatrixXd & > optional)
Constructor compatible with old-style derivatives.
Eigen::Matrix< double, traits< T >::dimension, traits< A >::dimension > type
Eigen::MatrixXd Jacobian
Jacobian size type.
OptionalJacobian()
Default constructor acts like boost::none.
OptionalJacobian(Jacobian &dynamic)
Construct from refrence to dynamic matrix.
OptionalJacobian(Jacobian &fixed)
Constructor that will usurp data of a fixed-size matrix.
Jacobian * operator->()
TODO: operator->()
: meta-function to generate JacobianTA optional reference Used mainly by Expressions ...
OptionalJacobian(Jacobian *pointer)
Construct from pointer to dynamic matrix.
Eigen::Map< Jacobian > * operator->()
operator->()
OptionalJacobian()
View on constructor argument, if given.
The matrix class, also used for vectors and row-vectors.
OptionalJacobian(Eigen::MatrixXd &dynamic)
Constructor that will resize a dynamic matrix (unless already correct)
OptionalJacobian(Jacobian *fixedPtr)
Constructor that will usurp data of a fixed-size matrix, pointer version.
Eigen::Matrix< double, Rows, Cols > Jacobian
Jacobian & operator*()
De-reference, like boost optional.
OptionalJacobian(boost::none_t)
Constructor with boost::none just makes empty.
Eigen::Map< Jacobian > & operator*()
De-reference, like boost optional.
OptionalJacobian(const boost::optional< Eigen::MatrixXd & > optional)
Constructor compatible with old-style derivatives.
Eigen::Map< Jacobian > map_