math/utils.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 CNRS
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid is distributed in the hope that it will be
10 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see
15 // <http://www.gnu.org/licenses/>.
16 //
17 
18 #ifndef __invdyn_math_utils_hpp__
19 #define __invdyn_math_utils_hpp__
20 
21 #include "tsid/math/fwd.hpp"
22 
23 #include <pinocchio/spatial/se3.hpp>
24 #include <pinocchio/spatial/explog.hpp>
25 
26 #include <iostream>
27 #include <fstream>
28 #include <vector>
29 
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
36 
37 namespace tsid {
38 template <typename T>
39 std::string toString(const T& v) {
40  std::stringstream ss;
41  ss << v;
42  return ss.str();
43 }
44 
45 template <typename T>
46 std::string toString(const std::vector<T>& v,
47  const std::string separator = ", ") {
48  std::stringstream ss;
49  for (int i = 0; i < v.size() - 1; i++) ss << v[i] << separator;
50  ss << v[v.size() - 1];
51  return ss.str();
52 }
53 
54 template <typename T, int n>
55 std::string toString(const Eigen::MatrixBase<T>& v,
56  const std::string separator = ", ") {
57  if (v.rows() > v.cols()) return toString(v.transpose(), separator);
58  std::stringstream ss;
59  ss << v;
60  return ss.str();
61 }
62 } // namespace tsid
63 
64 namespace tsid {
65 namespace math {
66 static const Eigen::IOFormat CleanFmt(1, 0, ", ", "\n", "[", "]");
67 
78 static const Eigen::IOFormat matlabPrintFormat(Eigen::FullPrecision,
79  Eigen::DontAlignCols, " ", ";\n",
80  "", "", "[", "];");
81 
85 void SE3ToXYZQUAT(const pinocchio::SE3& M, RefVector xyzQuat);
86 
91 void SE3ToVector(const pinocchio::SE3& M, RefVector vec);
92 
94 
95 void errorInSE3(const pinocchio::SE3& M, const pinocchio::SE3& Mdes,
97 
98 void solveWithDampingFromSvd(Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
100  double damping = 0.0);
101 
103  double damping = 0.0);
104 
105 void pseudoInverse(ConstRefMatrix A, RefMatrix Apinv, double tolerance,
106  unsigned int computationOptions = Eigen::ComputeThinU |
107  Eigen::ComputeThinV);
108 
110  Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
111  RefMatrix Apinv, double tolerance,
112  unsigned int computationOptions);
113 
115  Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
116  RefMatrix Apinv, double tolerance, double* nullSpaceBasisOfA,
117  int& nullSpaceRows, int& nullSpaceCols,
118  unsigned int computationOptions);
119 
121  Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition,
122  RefMatrix Apinv, double tolerance,
123  double dampingFactor,
124  unsigned int computationOptions = Eigen::ComputeThinU |
125  Eigen::ComputeThinV,
126  double* nullSpaceBasisOfA = 0, int* nullSpaceRows = 0,
127  int* nullSpaceCols = 0);
128 
130  const Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition, double tolerance,
131  double* nullSpaceBasisMatrix, int& rows, int& cols);
132 
134  const Eigen::JacobiSVD<Eigen::MatrixXd>& svdDecomposition, int rank,
135  double* nullSpaceBasisMatrix, int& rows, int& cols);
136 
137 template <typename Derived>
138 inline bool isFinite(const Eigen::MatrixBase<Derived>& x) {
139  return ((x - x).array() == (x - x).array()).all();
140 }
141 
142 template <typename Derived>
143 inline bool is_nan(const Eigen::MatrixBase<Derived>& x) {
144  return ((x.array() == x.array())).all();
145 }
146 
150 template <class Matrix>
151 bool writeMatrixToFile(const std::string& filename,
152  const Eigen::MatrixBase<Matrix>& matrix) {
153  typedef typename Matrix::Index Index;
154  typedef typename Matrix::Scalar Scalar;
155 
156  std::ofstream out(filename.c_str(),
157  std::ios::out | std::ios::binary | std::ios::trunc);
158  if (!out.is_open()) return false;
159  Index rows = matrix.rows(), cols = matrix.cols();
160  out.write((char*)(&rows), sizeof(Index));
161  out.write((char*)(&cols), sizeof(Index));
162  out.write((char*)matrix.data(), rows * cols * sizeof(Scalar));
163  out.close();
164  return true;
165 }
166 
170 template <class Matrix>
171 bool readMatrixFromFile(const std::string& filename,
172  const Eigen::MatrixBase<Matrix>& matrix) {
173  typedef typename Matrix::Index Index;
174  typedef typename Matrix::Scalar Scalar;
175 
176  std::ifstream in(filename.c_str(), std::ios::in | std::ios::binary);
177  if (!in.is_open()) return false;
178  Index rows = 0, cols = 0;
179  in.read((char*)(&rows), sizeof(Index));
180  in.read((char*)(&cols), sizeof(Index));
181 
182  Eigen::MatrixBase<Matrix>& matrix_ =
183  const_cast<Eigen::MatrixBase<Matrix>&>(matrix);
184 
185  matrix_.resize(rows, cols);
186  in.read((char*)matrix_.data(), rows * cols * sizeof(Scalar));
187  in.close();
188  return true;
189 }
190 
191 } // namespace math
192 } // namespace tsid
193 
194 #endif // ifndef __invdyn_math_utils_hpp__
demo_quadruped.v
v
Definition: demo_quadruped.py:80
test_Tasks.error
error
Definition: test_Tasks.py:70
ex_4_plan_LIPM_romeo.A
A
Definition: ex_4_plan_LIPM_romeo.py:110
tsid::math::isFinite
bool isFinite(const Eigen::MatrixBase< Derived > &x)
Definition: math/utils.hpp:138
tsid::math::errorInSE3
void errorInSE3(const pinocchio::SE3 &M, const pinocchio::SE3 &Mdes, pinocchio::Motion &error)
Definition: src/math/utils.cpp:46
pinocchio::SE3
context::SE3 SE3
i
int i
rows
int rows
tsid::math::dampedPseudoInverse
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)
Definition: src/math/utils.cpp:136
tsid::math::vectorToSE3
void vectorToSE3(RefVector vec, pinocchio::SE3 &M)
Definition: src/math/utils.cpp:38
tsid::math::RefMatrix
Eigen::Ref< Matrix > RefMatrix
Definition: math/fwd.hpp:50
tsid::math::pseudoInverse
void pseudoInverse(ConstRefMatrix A, RefMatrix Apinv, double tolerance, unsigned int computationOptions=Eigen::ComputeThinU|Eigen::ComputeThinV)
Definition: src/math/utils.cpp:82
b
Vec3f b
Index
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
tsid::math::Index
std::size_t Index
Definition: math/fwd.hpp:53
tsid::math::RefVector
Eigen::Ref< Vector > RefVector
Definition: math/fwd.hpp:47
fwd.hpp
tsid::math::readMatrixFromFile
bool readMatrixFromFile(const std::string &filename, const Eigen::MatrixBase< Matrix > &matrix)
Definition: math/utils.hpp:171
tsid::math::is_nan
bool is_nan(const Eigen::MatrixBase< Derived > &x)
Definition: math/utils.hpp:143
tsid::math::ConstRefVector
const typedef Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
tsid::math::SE3ToVector
void SE3ToVector(const pinocchio::SE3 &M, RefVector vec)
Definition: src/math/utils.cpp:30
tsid::math::svdSolveWithDamping
void svdSolveWithDamping(ConstRefMatrix A, ConstRefVector b, RefVector sol, double damping=0.0)
Definition: src/math/utils.cpp:73
tsid::math::solveWithDampingFromSvd
void solveWithDampingFromSvd(Eigen::JacobiSVD< Eigen::MatrixXd > &svd, ConstRefVector b, RefVector sol, double damping=0.0)
Definition: src/math/utils.cpp:55
tsid::math::Scalar
double Scalar
Definition: math/fwd.hpp:34
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
tsid::math::CleanFmt
static const Eigen::IOFormat CleanFmt(1, 0, ", ", "\n", "[", "]")
test_Solvers.damping
int damping
Definition: test_Solvers.py:15
tsid::math::matlabPrintFormat
static const Eigen::IOFormat matlabPrintFormat(Eigen::FullPrecision, Eigen::DontAlignCols, " ", ";\n", "", "", "[", "];")
test_Solvers.x
x
Definition: test_Solvers.py:67
tsid::math::SE3ToXYZQUAT
void SE3ToXYZQUAT(const pinocchio::SE3 &M, RefVector xyzQuat)
Definition: src/math/utils.cpp:23
tsid::math::ConstRefMatrix
const typedef Eigen::Ref< const Matrix > ConstRefMatrix
Definition: math/fwd.hpp:51
cols
int cols
demo_quadruped.filename
filename
Definition: demo_quadruped.py:46
tsid::math::writeMatrixToFile
bool writeMatrixToFile(const std::string &filename, const Eigen::MatrixBase< Matrix > &matrix)
Definition: math/utils.hpp:151
pinocchio::MotionTpl
tsid::toString
std::string toString(const T &v)
Definition: math/utils.hpp:39
tsid::math::nullSpaceBasisFromDecomposition
void nullSpaceBasisFromDecomposition(const Eigen::JacobiSVD< Eigen::MatrixXd > &svdDecomposition, double tolerance, double *nullSpaceBasisMatrix, int &rows, int &cols)
Definition: src/math/utils.cpp:175


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16