|
bool | gtsam::assert_equal (const Matrix &expected, const Matrix &actual, double tol) |
|
bool | gtsam::assert_equal (const std::list< Matrix > &As, const std::list< Matrix > &Bs, double tol) |
|
bool | gtsam::assert_inequal (const Matrix &A, const Matrix &B, double tol) |
|
Vector | gtsam::backSubstituteLower (const Matrix &L, const Vector &b, bool unit) |
|
Vector | gtsam::backSubstituteUpper (const Matrix &U, const Vector &b, bool unit) |
|
Vector | gtsam::backSubstituteUpper (const Vector &b, const Matrix &U, bool unit) |
|
Matrix | gtsam::cholesky_inverse (const Matrix &A) |
|
Matrix | gtsam::collect (const std::vector< const Matrix * > &matrices, size_t m, size_t n) |
|
Matrix | gtsam::collect (size_t nrMatrices,...) |
|
template<class MATRIX > |
const MATRIX::ConstColXpr | gtsam::column (const MATRIX &A, size_t j) |
|
Vector | gtsam::columnNormSquare (const Matrix &A) |
|
Matrix | gtsam::diag (const std::vector< Matrix > &Hs) |
|
std::tuple< int, double, Vector > | gtsam::DLT (const Matrix &A, double rank_tol) |
|
template<class MATRIX > |
bool | gtsam::equal_with_abs_tol (const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9) |
|
Matrix | gtsam::expm (const Matrix &A, size_t K) |
|
std::string | gtsam::formatMatrixIndented (const std::string &label, const Matrix &matrix, bool makeVectorHorizontal) |
|
void | gtsam::householder (Matrix &A, size_t k) |
|
void | gtsam::householder_ (Matrix &A, size_t k, bool copy_vectors) |
|
void | gtsam::inplace_QR (Matrix &A) |
|
template<typename Derived1 , typename Derived2 > |
void | gtsam::insertSub (Eigen::MatrixBase< Derived1 > &fullMatrix, const Eigen::MatrixBase< Derived2 > &subMatrix, size_t i, size_t j) |
|
Matrix | gtsam::inverse_square_root (const Matrix &A) |
|
bool | gtsam::linear_dependent (const Matrix &A, const Matrix &B, double tol) |
|
bool | gtsam::linear_independent (const Matrix &A, const Matrix &B, double tol) |
|
Matrix | gtsam::LLt (const Matrix &A) |
|
const Eigen::IOFormat & | gtsam::matlabFormat () |
|
bool | gtsam::operator!= (const Matrix &A, const Matrix &B) |
|
bool | gtsam::operator== (const Matrix &A, const Matrix &B) |
|
GTSAM_EXPORT std::istream & | gtsam::operator>> (std::istream &inputStream, Matrix &destinationMatrix) |
|
Vector | gtsam::operator^ (const Matrix &A, const Vector &v) |
|
GTSAM_EXPORT void | gtsam::print (const Matrix &A, const std::string &s, std::ostream &stream) |
|
GTSAM_EXPORT void | gtsam::print (const Matrix &A, const std::string &s="") |
|
template<class MATRIX > |
MATRIX | gtsam::prod (const MATRIX &A, const MATRIX &B) |
|
pair< Matrix, Matrix > | gtsam::qr (const Matrix &A) |
|
template<int OutM, int OutN, int OutOptions, int InM, int InN, int InOptions> |
Reshape< OutM, OutN, OutOptions, InM, InN, InOptions >::ReshapedType | gtsam::reshape (const Eigen::Matrix< double, InM, InN, InOptions > &m) |
|
template<class MATRIX > |
const MATRIX::ConstRowXpr | gtsam::row (const MATRIX &A, size_t j) |
|
Matrix | gtsam::RtR (const Matrix &A) |
|
GTSAM_EXPORT void | gtsam::save (const Matrix &A, const std::string &s, const std::string &filename) |
|
template<class Derived > |
Matrix3 | gtsam::skewSymmetric (const Eigen::MatrixBase< Derived > &w) |
|
Matrix3 | gtsam::skewSymmetric (double wx, double wy, double wz) |
|
Matrix | gtsam::stack (const std::vector< Matrix > &blocks) |
|
Matrix | gtsam::stack (size_t nrMatrices,...) |
|
template<class MATRIX > |
Eigen::Block< const MATRIX > | gtsam::sub (const MATRIX &A, size_t i1, size_t i2, size_t j1, size_t j2) |
|
void | gtsam::svd (const Matrix &A, Matrix &U, Vector &S, Matrix &V) |
|
Matrix | gtsam::trans (const Matrix &A) |
|
Matrix | gtsam::vector_scale (const Matrix &A, const Vector &v, bool inf_mask) |
|
Matrix | gtsam::vector_scale (const Vector &v, const Matrix &A, bool inf_mask) |
|
void | gtsam::vector_scale_inplace (const Vector &v, Matrix &A, bool inf_mask) |
|
list< std::tuple< Vector, double, double > > | gtsam::weighted_eliminate (Matrix &A, Vector &b, const Vector &sigmas) |
|
template<class MATRIX > |
void | gtsam::zeroBelowDiagonal (MATRIX &A, size_t cols=0) |
|
typedef and functions to augment Eigen's MatrixXd
- Author
- Christian Potthast
-
Kai Ni
-
Frank Dellaert
-
Alex Cunningham
-
Alex Hagiopol
-
Varun Agrawal
Definition in file base/Matrix.h.