Classes | Typedefs | Functions | Variables
tsid::math Namespace Reference

Classes

class  ConstraintBase
 Abstract class representing a linear equality/inequality constraint. Equality constraints are represented by a matrix A and a vector b: A*x = b Inequality constraints are represented by a matrix A and two vectors lb and ub: lb <= A*x <= ub Bounds are represented by two vectors lb and ub: lb <= x <= ub. More...
 
class  ConstraintBound
 
class  ConstraintEquality
 
class  ConstraintInequality
 

Typedefs

typedef std::size_t Index
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::DynamicMatrix
 
typedef Eigen::Matrix< Scalar, 3, Eigen::DynamicMatrix3x
 
typedef Eigen::Ref< MatrixRefMatrix
 
typedef Eigen::Ref< VectorRefVector
 
typedef Eigen::Ref< Vector3RefVector3
 
typedef double Scalar
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
 
typedef Eigen::Matrix< Scalar, 3, 1 > Vector3
 
typedef Eigen::Matrix< Scalar, 6, 1 > Vector6
 
typedef Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
 
typedef Eigen::VectorXi VectorXi
 

Functions

static const Eigen::IOFormat CleanFmt (1, 0, ", ", "\n", "[", "]")
 
void dampedPseudoInverse (ConstRefMatrix A, Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, RefMatrix Apinv, double tolerance, double dampingFactor, unsigned int computationOptions=Eigen::ComputeThinU|Eigen::ComputeThinV, double *nullSpaceBasisOfA=0, int *nullSpaceRows=0, int *nullSpaceCols=0)
 
void errorInSE3 (const pinocchio::SE3 &M, const pinocchio::SE3 &Mdes, pinocchio::Motion &error)
 
template<typename Derived >
bool is_nan (const Eigen::MatrixBase< Derived > &x)
 
template<typename Derived >
bool isFinite (const Eigen::MatrixBase< Derived > &x)
 
static const Eigen::IOFormat matlabPrintFormat (Eigen::FullPrecision, Eigen::DontAlignCols, " ", ";\n", "", "", "[", "];")
 
void nullSpaceBasisFromDecomposition (const Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, double tolerance, double *nullSpaceBasisMatrix, int &rows, int &cols)
 
void nullSpaceBasisFromDecomposition (const Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, int rank, double *nullSpaceBasisMatrix, int &rows, int &cols)
 
void pseudoInverse (ConstRefMatrix A, Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, RefMatrix Apinv, double tolerance, double *nullSpaceBasisOfA, int &nullSpaceRows, int &nullSpaceCols, unsigned int computationOptions)
 
void pseudoInverse (ConstRefMatrix A, Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, RefMatrix Apinv, double tolerance, unsigned int computationOptions)
 
void pseudoInverse (ConstRefMatrix A, RefMatrix Apinv, double tolerance, unsigned int computationOptions=Eigen::ComputeThinU|Eigen::ComputeThinV)
 
template<class Matrix >
bool readMatrixFromFile (const std::string &filename, const Eigen::MatrixBase< Matrix > &matrix)
 
void SE3ToVector (const pinocchio::SE3 &M, RefVector vec)
 
void SE3ToXYZQUAT (const pinocchio::SE3 &M, RefVector xyzQuat)
 
void solveWithDampingFromSvd (Eigen::JacobiSVD< Eigen::MatrixXd > &svd, ConstRefVector b, RefVector sol, double damping=0.0)
 
void svdSolveWithDamping (ConstRefMatrix A, ConstRefVector b, RefVector sol, double damping=0.0)
 
void vectorToSE3 (RefVector vec, pinocchio::SE3 &M)
 
template<class Matrix >
bool writeMatrixToFile (const std::string &filename, const Eigen::MatrixBase< Matrix > &matrix)
 

Variables

const typedef Eigen::Ref< const MatrixConstRefMatrix
 
const typedef Eigen::Ref< const VectorConstRefVector
 
const typedef Eigen::Ref< const Vector3ConstRefVector3
 

Typedef Documentation

◆ Index

typedef std::size_t tsid::math::Index

Definition at line 53 of file math/fwd.hpp.

◆ Matrix

Definition at line 36 of file math/fwd.hpp.

◆ Matrix3x

typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic> tsid::math::Matrix3x

Definition at line 42 of file math/fwd.hpp.

◆ RefMatrix

typedef Eigen::Ref<Matrix> tsid::math::RefMatrix

Definition at line 50 of file math/fwd.hpp.

◆ RefVector

typedef Eigen::Ref<Vector> tsid::math::RefVector

Definition at line 47 of file math/fwd.hpp.

◆ RefVector3

typedef Eigen::Ref<Vector3> tsid::math::RefVector3

Definition at line 44 of file math/fwd.hpp.

◆ Scalar

typedef double tsid::math::Scalar

Definition at line 34 of file math/fwd.hpp.

◆ Vector

typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> tsid::math::Vector

Definition at line 35 of file math/fwd.hpp.

◆ Vector3

typedef Eigen::Matrix<Scalar, 3, 1> tsid::math::Vector3

Definition at line 40 of file math/fwd.hpp.

◆ Vector6

typedef Eigen::Matrix<Scalar, 6, 1> tsid::math::Vector6

Definition at line 41 of file math/fwd.hpp.

◆ VectorXb

typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> tsid::math::VectorXb

Definition at line 38 of file math/fwd.hpp.

◆ VectorXi

typedef Eigen::VectorXi tsid::math::VectorXi

Definition at line 37 of file math/fwd.hpp.

Function Documentation

◆ CleanFmt()

static const Eigen::IOFormat tsid::math::CleanFmt ( ,
,
,
,
"\n"  ,
""  [", "] 
)
static

◆ dampedPseudoInverse()

void tsid::math::dampedPseudoInverse ( ConstRefMatrix  A,
Eigen::JacobiSVD< Eigen::MatrixXd > &  svdDecomposition,
RefMatrix  Apinv,
double  tolerance,
double  dampingFactor,
unsigned int  computationOptions = Eigen::ComputeThinU | Eigen::ComputeThinV,
double *  nullSpaceBasisOfA = 0,
int *  nullSpaceRows = 0,
int *  nullSpaceCols = 0 
)

Definition at line 136 of file src/math/utils.cpp.

◆ errorInSE3()

void tsid::math::errorInSE3 ( const pinocchio::SE3 M,
const pinocchio::SE3 Mdes,
pinocchio::Motion error 
)

Definition at line 46 of file src/math/utils.cpp.

◆ is_nan()

template<typename Derived >
bool tsid::math::is_nan ( const Eigen::MatrixBase< Derived > &  x)
inline

Definition at line 143 of file math/utils.hpp.

◆ isFinite()

template<typename Derived >
bool tsid::math::isFinite ( const Eigen::MatrixBase< Derived > &  x)
inline

Definition at line 138 of file math/utils.hpp.

◆ matlabPrintFormat()

static const Eigen::IOFormat tsid::math::matlabPrintFormat ( Eigen::FullPrecision  ,
Eigen::DontAlignCols  ,
" "  ,
";\n"  ,
""  ,
""  ,
";"  [", "] 
)
static

List of available parameters of IOFormat constructor: precision number of digits for floating point values, or one of the special constants StreamPrecision and FullPrecision. flags either 0, or DontAlignCols, which allows to disable the alignment of columns, resulting in faster code. coeffSeparator string printed between two coefficients of the same row rowSeparator string printed between two rows rowPrefix string printed at the beginning of each row rowSuffix string printed at the end of each row matPrefix string printed at the beginning of the matrix matSuffix string printed at the end of the matrix

◆ nullSpaceBasisFromDecomposition() [1/2]

void tsid::math::nullSpaceBasisFromDecomposition ( const Eigen::JacobiSVD< Eigen::MatrixXd > &  svdDecomposition,
double  tolerance,
double *  nullSpaceBasisMatrix,
int &  rows,
int &  cols 
)

Definition at line 175 of file src/math/utils.cpp.

◆ nullSpaceBasisFromDecomposition() [2/2]

void tsid::math::nullSpaceBasisFromDecomposition ( const Eigen::JacobiSVD< Eigen::MatrixXd > &  svdDecomposition,
int  rank,
double *  nullSpaceBasisMatrix,
int &  rows,
int &  cols 
)

Definition at line 191 of file src/math/utils.cpp.

◆ pseudoInverse() [1/3]

void tsid::math::pseudoInverse ( ConstRefMatrix  A,
Eigen::JacobiSVD< Eigen::MatrixXd > &  svdDecomposition,
RefMatrix  Apinv,
double  tolerance,
double *  nullSpaceBasisOfA,
int &  nullSpaceRows,
int &  nullSpaceCols,
unsigned int  computationOptions 
)

Definition at line 100 of file src/math/utils.cpp.

◆ pseudoInverse() [2/3]

void tsid::math::pseudoInverse ( ConstRefMatrix  A,
Eigen::JacobiSVD< Eigen::MatrixXd > &  svdDecomposition,
RefMatrix  Apinv,
double  tolerance,
unsigned int  computationOptions 
)

Definition at line 90 of file src/math/utils.cpp.

◆ pseudoInverse() [3/3]

void tsid::math::pseudoInverse ( ConstRefMatrix  A,
RefMatrix  Apinv,
double  tolerance,
unsigned int  computationOptions = Eigen::ComputeThinU | Eigen::ComputeThinV 
)

Definition at line 82 of file src/math/utils.cpp.

◆ readMatrixFromFile()

template<class Matrix >
bool tsid::math::readMatrixFromFile ( const std::string &  filename,
const Eigen::MatrixBase< Matrix > &  matrix 
)

Read a matrix from the specified input binary file.

Definition at line 171 of file math/utils.hpp.

◆ SE3ToVector()

void tsid::math::SE3ToVector ( const pinocchio::SE3 M,
RefVector  vec 
)

Convert the input SE3 object to a 12D vector of floats [X,Y,Z,R11,R12,R13,R14,...].

Definition at line 30 of file src/math/utils.cpp.

◆ SE3ToXYZQUAT()

void tsid::math::SE3ToXYZQUAT ( const pinocchio::SE3 M,
RefVector  xyzQuat 
)

Convert the input SE3 object to a 7D vector of floats [X,Y,Z,Q1,Q2,Q3,Q4].

Definition at line 23 of file src/math/utils.cpp.

◆ solveWithDampingFromSvd()

void tsid::math::solveWithDampingFromSvd ( Eigen::JacobiSVD< Eigen::MatrixXd > &  svd,
ConstRefVector  b,
RefVector  sol,
double  damping = 0.0 
)

Definition at line 55 of file src/math/utils.cpp.

◆ svdSolveWithDamping()

void tsid::math::svdSolveWithDamping ( ConstRefMatrix  A,
ConstRefVector  b,
RefVector  sol,
double  damping = 0.0 
)

Definition at line 73 of file src/math/utils.cpp.

◆ vectorToSE3()

void tsid::math::vectorToSE3 ( RefVector  vec,
pinocchio::SE3 M 
)

Definition at line 38 of file src/math/utils.cpp.

◆ writeMatrixToFile()

template<class Matrix >
bool tsid::math::writeMatrixToFile ( const std::string &  filename,
const Eigen::MatrixBase< Matrix > &  matrix 
)

Write the specified matrix to a binary file with the specified name.

Definition at line 151 of file math/utils.hpp.

Variable Documentation

◆ ConstRefMatrix

const typedef Eigen::Ref<const Matrix> tsid::math::ConstRefMatrix

Definition at line 51 of file math/fwd.hpp.

◆ ConstRefVector

const typedef Eigen::Ref<const Vector> tsid::math::ConstRefVector

Definition at line 48 of file math/fwd.hpp.

◆ ConstRefVector3

const typedef Eigen::Ref<const Vector3> tsid::math::ConstRefVector3

Definition at line 45 of file math/fwd.hpp.



tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17