Namespaces | Macros | Functions
math/utils.hpp File Reference
#include "tsid/math/fwd.hpp"
#include <pinocchio/spatial/se3.hpp>
#include <pinocchio/spatial/explog.hpp>
#include <iostream>
#include <fstream>
#include <vector>
Include dependency graph for math/utils.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 tsid
 
 tsid::math
 

Macros

#define PRINT_MATRIX(a)
 
#define PRINT_VECTOR(a)
 

Functions

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

Macro Definition Documentation

◆ PRINT_MATRIX

#define PRINT_MATRIX (   a)
Value:
std::cout << #a << "(" << a.rows() << "x" << a.cols() << "):\n" \
<< a.format(math::CleanFmt) << std::endl
static const Eigen::IOFormat CleanFmt(1, 0, ", ", "\, "[", "]")
Vec3f a

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

◆ PRINT_VECTOR

#define PRINT_VECTOR (   a)
Value:
std::cout << #a << "(" << a.rows() << "x" << a.cols() \
<< "): " << a.transpose().format(math::CleanFmt) << std::endl
static const Eigen::IOFormat CleanFmt(1, 0, ", ", "\, "[", "]")
Vec3f a

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



tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51