Classes | Namespaces | Macros | Typedefs | Functions
base/Matrix.h File Reference
#include <gtsam/base/OptionalJacobian.h>
#include <gtsam/base/Vector.h>
#include <gtsam/config.h>
#include <boost/format.hpp>
#include <boost/function.hpp>
#include <boost/tuple/tuple.hpp>
#include <boost/math/special_functions/fpclassify.hpp>
#include <boost/serialization/nvp.hpp>
#include <boost/serialization/array.hpp>
#include <boost/serialization/split_free.hpp>
Include dependency graph for base/Matrix.h:

Go to the source code of this file.

Classes

struct  gtsam::MultiplyWithInverse< N >
 
struct  gtsam::MultiplyWithInverseFunction< T, N >
 
struct  gtsam::Reshape< OutM, OutN, OutOptions, InM, InN, InOptions >
 Reshape functor. More...
 
struct  gtsam::Reshape< M, M, InOptions, M, M, InOptions >
 Reshape specialization that does nothing as shape stays the same (needed to not be ambiguous for square input equals square output) More...
 
struct  gtsam::Reshape< M, N, InOptions, M, N, InOptions >
 Reshape specialization that does nothing as shape stays the same. More...
 
struct  gtsam::Reshape< N, M, InOptions, M, N, InOptions >
 Reshape specialization that does transpose. More...
 

Namespaces

 boost
 
 boost::serialization
 
 gtsam
 traits
 

Macros

#define GTSAM_MAKE_MATRIX_DEFS(N)
 

Typedefs

typedef Eigen::Block< const Matrix > gtsam::ConstSubMatrix
 
typedef Eigen::MatrixXd gtsam::Matrix
 
typedef Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajorgtsam::MatrixRowMajor
 
typedef Eigen::Block< Matrix > gtsam::SubMatrix
 

Functions

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)
 
boost::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)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (1)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (2)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (3)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (4)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (5)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (6)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (7)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (8)
 
 gtsam::GTSAM_MAKE_MATRIX_DEFS (9)
 
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)
 
template<class Archive , typename Scalar_ , int Rows_, int Cols_, int Ops_, int MaxRows_, int MaxCols_>
void boost::serialization::load (Archive &ar, Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int)
 
const Eigen::IOFormatgtsam::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 Archive , typename Scalar_ , int Rows_, int Cols_, int Ops_, int MaxRows_, int MaxCols_>
void boost::serialization::save (Archive &ar, const Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int)
 
template<class Archive , typename Scalar_ , int Rows_, int Cols_, int Ops_, int MaxRows_, int MaxCols_>
void boost::serialization::serialize (Archive &ar, Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int version)
 
template<class Archive >
void boost::serialization::serialize (Archive &ar, gtsam::Matrix &m, const unsigned int version)
 
Matrix3 gtsam::skewSymmetric (double wx, double wy, double wz)
 
template<class Derived >
Matrix3 gtsam::skewSymmetric (const Eigen::MatrixBase< Derived > &w)
 
Matrix gtsam::stack (size_t nrMatrices,...)
 
Matrix gtsam::stack (const std::vector< Matrix > &blocks)
 
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 Vector &v, const Matrix &A, bool inf_mask)
 
Matrix gtsam::vector_scale (const Matrix &A, const Vector &v, bool inf_mask)
 
void gtsam::vector_scale_inplace (const Vector &v, Matrix &A, bool inf_mask)
 
list< boost::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)
 

Macro Definition Documentation

#define GTSAM_MAKE_MATRIX_DEFS (   N)
Value:
typedef Eigen::Matrix<double, 2, N> Matrix2##N; \
typedef Eigen::Matrix<double, 3, N> Matrix3##N; \
typedef Eigen::Matrix<double, 4, N> Matrix4##N; \
typedef Eigen::Matrix<double, 5, N> Matrix5##N; \
typedef Eigen::Matrix<double, 6, N> Matrix6##N; \
typedef Eigen::Matrix<double, 7, N> Matrix7##N; \
typedef Eigen::Matrix<double, 8, N> Matrix8##N; \
static const Eigen::MatrixBase<Matrix##N>::IdentityReturnType I_##N##x##N = Matrix##N::Identity(); \
Generic expression of a matrix where all coefficients are defined by a functor.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define N
Definition: gksort.c:12
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x

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



gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:32