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::Dynamic > | Matrix |
typedef Eigen::Matrix< Scalar, 3, Eigen::Dynamic > | Matrix3x |
typedef Eigen::Ref< Matrix > | RefMatrix |
typedef Eigen::Ref< Vector > | RefVector |
typedef Eigen::Ref< Vector3 > | RefVector3 |
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 Matrix > | ConstRefMatrix |
const typedef Eigen::Ref< const Vector > | ConstRefVector |
const typedef Eigen::Ref< const Vector3 > | ConstRefVector3 |
typedef std::size_t tsid::math::Index |
Definition at line 53 of file math/fwd.hpp.
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> tsid::math::Matrix |
Definition at line 36 of file math/fwd.hpp.
typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic> tsid::math::Matrix3x |
Definition at line 42 of file math/fwd.hpp.
typedef Eigen::Ref<Matrix> tsid::math::RefMatrix |
Definition at line 50 of file math/fwd.hpp.
typedef Eigen::Ref<Vector> tsid::math::RefVector |
Definition at line 47 of file math/fwd.hpp.
typedef Eigen::Ref<Vector3> tsid::math::RefVector3 |
Definition at line 44 of file math/fwd.hpp.
typedef double tsid::math::Scalar |
Definition at line 34 of file math/fwd.hpp.
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1> tsid::math::Vector |
Definition at line 35 of file math/fwd.hpp.
typedef Eigen::Matrix<Scalar, 3, 1> tsid::math::Vector3 |
Definition at line 40 of file math/fwd.hpp.
typedef Eigen::Matrix<Scalar, 6, 1> tsid::math::Vector6 |
Definition at line 41 of file math/fwd.hpp.
typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> tsid::math::VectorXb |
Definition at line 38 of file math/fwd.hpp.
typedef Eigen::VectorXi tsid::math::VectorXi |
Definition at line 37 of file math/fwd.hpp.
|
static |
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.
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.
|
inline |
Definition at line 143 of file math/utils.hpp.
|
inline |
Definition at line 138 of file math/utils.hpp.
|
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
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.
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.
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.
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.
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.
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.
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.
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.
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.
void tsid::math::svdSolveWithDamping | ( | ConstRefMatrix | A, |
ConstRefVector | b, | ||
RefVector | sol, | ||
double | damping = 0.0 |
||
) |
Definition at line 73 of file src/math/utils.cpp.
void tsid::math::vectorToSE3 | ( | RefVector | vec, |
pinocchio::SE3 & | M | ||
) |
Definition at line 38 of file src/math/utils.cpp.
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.
const typedef Eigen::Ref<const Matrix> tsid::math::ConstRefMatrix |
Definition at line 51 of file math/fwd.hpp.
const typedef Eigen::Ref<const Vector> tsid::math::ConstRefVector |
Definition at line 48 of file math/fwd.hpp.
const typedef Eigen::Ref<const Vector3> tsid::math::ConstRefVector3 |
Definition at line 45 of file math/fwd.hpp.