Go to the documentation of this file.
18 #ifndef __invdyn_math_utils_hpp__
19 #define __invdyn_math_utils_hpp__
23 #include <pinocchio/spatial/se3.hpp>
24 #include <pinocchio/spatial/explog.hpp>
30 #define PRINT_VECTOR(a) \
31 std::cout << #a << "(" << a.rows() << "x" << a.cols() \
32 << "): " << a.transpose().format(math::CleanFmt) << std::endl
33 #define PRINT_MATRIX(a) \
34 std::cout << #a << "(" << a.rows() << "x" << a.cols() << "):\n" \
35 << a.format(math::CleanFmt) << std::endl
47 const std::string separator =
", ") {
49 for (
int i = 0;
i <
v.size() - 1;
i++) ss <<
v[
i] << separator;
50 ss <<
v[
v.size() - 1];
54 template <
typename T,
int n>
56 const std::string separator =
", ") {
57 if (
v.rows() >
v.cols())
return toString(
v.transpose(), separator);
66 static const Eigen::IOFormat
CleanFmt(1, 0,
", ",
"\n",
"[",
"]");
79 Eigen::DontAlignCols,
" ",
";\n",
106 unsigned int computationOptions = Eigen::ComputeThinU |
107 Eigen::ComputeThinV);
110 Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
112 unsigned int computationOptions);
115 Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
116 RefMatrix Apinv,
double tolerance,
double* nullSpaceBasisOfA,
117 int& nullSpaceRows,
int& nullSpaceCols,
118 unsigned int computationOptions);
121 Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
123 double dampingFactor,
124 unsigned int computationOptions = Eigen::ComputeThinU |
126 double* nullSpaceBasisOfA = 0,
int* nullSpaceRows = 0,
127 int* nullSpaceCols = 0);
130 const Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
double tolerance,
131 double* nullSpaceBasisMatrix,
int& rows,
int& cols);
134 const Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
int rank,
135 double* nullSpaceBasisMatrix,
int& rows,
int& cols);
137 template <
typename Derived>
138 inline bool isFinite(
const Eigen::MatrixBase<Derived>&
x) {
139 return ((
x -
x).array() == (
x -
x).array()).all();
142 template <
typename Derived>
143 inline bool is_nan(
const Eigen::MatrixBase<Derived>&
x) {
144 return ((
x.array() ==
x.array())).all();
150 template <
class Matrix>
152 const Eigen::MatrixBase<Matrix>& matrix) {
157 std::ios::out | std::ios::binary | std::ios::trunc);
158 if (!out.is_open())
return false;
160 out.write((
char*)(&
rows),
sizeof(
Index));
161 out.write((
char*)(&
cols),
sizeof(
Index));
170 template <
class Matrix>
172 const Eigen::MatrixBase<Matrix>& matrix) {
176 std::ifstream in(
filename.c_str(), std::ios::in | std::ios::binary);
177 if (!in.is_open())
return false;
182 Eigen::MatrixBase<Matrix>& matrix_ =
183 const_cast<Eigen::MatrixBase<Matrix>&
>(matrix);
194 #endif // ifndef __invdyn_math_utils_hpp__
bool isFinite(const Eigen::MatrixBase< Derived > &x)
void errorInSE3(const pinocchio::SE3 &M, const pinocchio::SE3 &Mdes, pinocchio::Motion &error)
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 vectorToSE3(RefVector vec, pinocchio::SE3 &M)
Eigen::Ref< Matrix > RefMatrix
void pseudoInverse(ConstRefMatrix A, RefMatrix Apinv, double tolerance, unsigned int computationOptions=Eigen::ComputeThinU|Eigen::ComputeThinV)
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
Eigen::Ref< Vector > RefVector
bool readMatrixFromFile(const std::string &filename, const Eigen::MatrixBase< Matrix > &matrix)
bool is_nan(const Eigen::MatrixBase< Derived > &x)
const typedef Eigen::Ref< const Vector > ConstRefVector
void SE3ToVector(const pinocchio::SE3 &M, RefVector vec)
void svdSolveWithDamping(ConstRefMatrix A, ConstRefVector b, RefVector sol, double damping=0.0)
void solveWithDampingFromSvd(Eigen::JacobiSVD< Eigen::MatrixXd > &svd, ConstRefVector b, RefVector sol, double damping=0.0)
static const Eigen::IOFormat CleanFmt(1, 0, ", ", "\n", "[", "]")
static const Eigen::IOFormat matlabPrintFormat(Eigen::FullPrecision, Eigen::DontAlignCols, " ", ";\n", "", "", "[", "];")
void SE3ToXYZQUAT(const pinocchio::SE3 &M, RefVector xyzQuat)
const typedef Eigen::Ref< const Matrix > ConstRefMatrix
bool writeMatrixToFile(const std::string &filename, const Eigen::MatrixBase< Matrix > &matrix)
std::string toString(const T &v)
void nullSpaceBasisFromDecomposition(const Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, double tolerance, double *nullSpaceBasisMatrix, int &rows, int &cols)
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16