5 #ifndef __pinocchio_algorithm_contact_cholesky_hpp__
6 #define __pinocchio_algorithm_contact_cholesky_hpp__
21 template<
typename MatrixLike,
int ColsAtCompileTime = MatrixLike::ColsAtCompileTime>
24 template<
typename MatrixLike,
int ColsAtCompileTime = MatrixLike::ColsAtCompileTime>
27 template<
typename MatrixLike,
int ColsAtCompileTime = MatrixLike::ColsAtCompileTime>
30 template<
typename MatrixLike,
int ColsAtCompileTime = MatrixLike::ColsAtCompileTime>
33 template<
typename Scalar,
int Options,
typename VectorLike>
36 const Eigen::DenseIndex col,
37 const Eigen::MatrixBase<VectorLike> & vec);
40 template<
typename _ContactCholeskyDecomposition>
54 template<
typename _Scalar,
int _Options>
58 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
69 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> Vector;
70 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> Matrix;
78 typedef Eigen::Matrix<Eigen::DenseIndex, Eigen::Dynamic, 1, Options> IndexVector;
80 typedef Eigen::Matrix<bool, Eigen::Dynamic, 1, Options> BooleanVector;
86 Slice(
const Eigen::DenseIndex & first_index,
const Eigen::DenseIndex &
size)
87 : first_index(first_index)
92 Eigen::DenseIndex first_index;
93 Eigen::DenseIndex
size;
97 DelassusCholeskyExpression;
100 typedef std::vector<Slice> SliceVector;
101 typedef std::vector<SliceVector> VectorOfSliceVector;
114 template<
typename S1,
int O1,
template<
typename,
int>
class JointCollectionTpl>
122 allocate(
model, empty_contact_models);
135 template<
typename S1,
int O1,
template<
typename,
int>
class JointCollectionTpl,
class Allocator>
158 template<
typename S1,
int O1,
template<
typename,
int>
class JointCollectionTpl,
class Allocator>
168 Matrix getInverseOperationalSpaceInertiaMatrix()
const
170 Matrix
res(constraintDim(), constraintDim());
171 getInverseOperationalSpaceInertiaMatrix(
res);
175 template<
typename MatrixType>
176 void getInverseOperationalSpaceInertiaMatrix(
const Eigen::MatrixBase<MatrixType> &
res)
const
181 const ConstBlockXpr U1 =
U.topLeftCorner(constraintDim(), constraintDim());
185 OSIMinv_tmp.noalias() =
D.head(constraintDim()).asDiagonal() * U1.adjoint();
186 res_.noalias() = -U1 * OSIMinv_tmp;
192 DelassusCholeskyExpression getDelassusCholeskyExpression()
const
194 return DelassusCholeskyExpression(*
this);
200 Matrix getOperationalSpaceInertiaMatrix()
const
202 Matrix
res(constraintDim(), constraintDim());
203 getOperationalSpaceInertiaMatrix(
res);
207 template<
typename MatrixType>
208 void getOperationalSpaceInertiaMatrix(
const Eigen::MatrixBase<MatrixType> & res_)
const
214 const Eigen::TriangularView<ConstBlockXpr, Eigen::UnitUpper> U1 =
215 U.topLeftCorner(constraintDim(), constraintDim())
216 .template triangularView<Eigen::UnitUpper>();
220 U1.solveInPlace(U1inv);
221 OSIMinv_tmp.noalias() = -U1inv.adjoint() * Dinv.head(constraintDim()).asDiagonal();
222 res.noalias() = OSIMinv_tmp * U1inv;
226 Matrix getInverseMassMatrix()
const
229 getInverseMassMatrix(
res);
233 template<
typename MatrixType>
234 void getInverseMassMatrix(
const Eigen::MatrixBase<MatrixType> & res_)
const
240 const Eigen::TriangularView<ConstBlockXpr, Eigen::UnitUpper> U4 =
241 U.bottomRightCorner(
nv,
nv).template triangularView<Eigen::UnitUpper>();
245 U4.solveInPlace(U4inv);
246 Minv_tmp.noalias() = U4inv.adjoint() * Dinv.tail(
nv).asDiagonal();
247 res.noalias() = Minv_tmp * U4inv;
251 template<
typename MatrixType>
252 void getJMinv(
const Eigen::MatrixBase<MatrixType> & res_)
const
257 const Eigen::TriangularView<ConstBlockXpr, Eigen::UnitUpper> U4 =
258 U.bottomRightCorner(
nv,
nv).template triangularView<Eigen::UnitUpper>();
259 ConstBlockXpr U2 =
U.topRightCorner(constraintDim(),
nv);
262 U4.solveInPlace(U4inv);
263 res.noalias() = U2 * U4inv;
289 template<
typename,
int>
class JointCollectionTpl,
290 class ConstraintModelAllocator,
291 class ConstraintDataAllocator>
297 const S1
mu = S1(0.))
321 template<
typename,
int>
class JointCollectionTpl,
322 class ConstraintModelAllocator,
323 class ConstraintDataAllocator,
330 const Eigen::MatrixBase<VectorLike> & mus);
340 template<
typename VectorLike>
341 void updateDamping(
const Eigen::MatrixBase<VectorLike> & mus);
350 void updateDamping(
const Scalar &
mu);
353 Eigen::DenseIndex
size()
const
360 Eigen::DenseIndex constraintDim()
const
366 Eigen::DenseIndex numContacts()
const
382 template<
typename MatrixLike>
383 void solveInPlace(
const Eigen::MatrixBase<MatrixLike> &
mat)
const;
394 template<
typename MatrixLike>
395 Matrix
solve(
const Eigen::MatrixBase<MatrixLike> &
mat)
const;
402 template<
typename S1,
int O1,
template<
typename,
int>
class JointCollectionTpl>
408 template<
typename MatrixLike>
409 void Uv(
const Eigen::MatrixBase<MatrixLike> &
mat)
const;
411 template<
typename MatrixLike>
412 void Utv(
const Eigen::MatrixBase<MatrixLike> &
mat)
const;
414 template<
typename MatrixLike>
415 void Uiv(
const Eigen::MatrixBase<MatrixLike> &
mat)
const;
417 template<
typename MatrixLike>
418 void Utiv(
const Eigen::MatrixBase<MatrixLike> &
mat)
const;
422 Matrix matrix()
const;
425 template<
typename MatrixType>
426 void matrix(
const Eigen::MatrixBase<MatrixType> &
res)
const;
432 template<
typename MatrixType>
433 void inverse(
const Eigen::MatrixBase<MatrixType> &
res)
const;
441 template<
typename MatrixLike,
int ColsAtCompileTime>
444 template<
typename MatrixLike,
int ColsAtCompileTime>
447 template<
typename MatrixLike,
int ColsAtCompileTime>
450 template<
typename MatrixLike,
int ColsAtCompileTime>
456 template<
typename Scalar,
int Options,
typename VectorLike>
459 const Eigen::DenseIndex col,
460 const Eigen::MatrixBase<VectorLike> &
vec);
463 template<
typename S1,
int O1>
466 template<
typename S1,
int O1>
471 IndexVector parents_fromRow;
472 IndexVector nv_subtree_fromRow;
475 IndexVector last_child;
480 Eigen::DenseIndex
nv;
483 Eigen::DenseIndex num_contacts;
485 VectorOfSliceVector rowise_sparsity_pattern;
488 mutable Matrix U1inv;
490 mutable Matrix U4inv;
492 mutable RowMatrix OSIMinv_tmp, Minv_tmp;
495 template<
typename ContactCholeskyDecomposition>
503 typedef typename ContactCholeskyDecomposition::Matrix
Matrix;
504 typedef typename ContactCholeskyDecomposition::Vector
Vector;
507 template<
typename _ContactCholeskyDecomposition>
513 typedef typename ContactCholeskyDecomposition::Vector
Vector;
514 typedef typename ContactCholeskyDecomposition::Matrix
Matrix;
515 typedef typename ContactCholeskyDecomposition::RowMatrix
RowMatrix;
535 template<
typename MatrixIn,
typename MatrixOut>
537 const Eigen::MatrixBase<MatrixIn> & x,
const Eigen::MatrixBase<MatrixOut> &
res)
const
546 self.U.topLeftCorner(
self.constraintDim(),
self.constraintDim());
548 if (
x.cols() <=
self.constraintDim())
552 self.constraintDim(),
x.cols());
554 triangularMatrixMatrixProduct<Eigen::UnitLower>(U1.adjoint(),
x.derived(), tmp_mat);
555 tmp_mat.array().colwise() *= -
self.D.head(
self.constraintDim()).array();
557 triangularMatrixMatrixProduct<Eigen::UnitUpper>(U1, tmp_mat,
res.const_cast_derived());
563 triangularMatrixMatrixProduct<Eigen::UnitLower>(U1.adjoint(),
x.derived(), tmp_mat);
564 tmp_mat.array().colwise() *= -
self.D.head(
self.constraintDim()).array();
566 triangularMatrixMatrixProduct<Eigen::UnitUpper>(U1, tmp_mat,
res.const_cast_derived());
572 template<
typename MatrixDerived>
574 operator*(
const Eigen::MatrixBase<MatrixDerived> & x)
const
577 ReturnType
res(
self.constraintDim(),
x.cols());
582 template<
typename MatrixDerived>
583 void solveInPlace(
const Eigen::MatrixBase<MatrixDerived> & x)
const
587 const Eigen::TriangularView<RowMatrixConstBlockXpr, Eigen::UnitUpper> U1 =
588 self.U.topLeftCorner(
self.constraintDim(),
self.constraintDim())
589 .template triangularView<Eigen::UnitUpper>();
592 U1.solveInPlace(
x.const_cast_derived());
593 x.const_cast_derived().array().colwise() *= -
self.Dinv.head(
self.constraintDim()).array();
594 U1.adjoint().solveInPlace(x);
598 template<
typename MatrixDerivedIn,
typename MatrixDerivedOut>
600 const Eigen::MatrixBase<MatrixDerivedIn> & x,
601 const Eigen::MatrixBase<MatrixDerivedOut> &
res)
const
603 res.const_cast_derived() =
x;
604 solveInPlace(
res.const_cast_derived());
607 template<
typename MatrixDerived>
609 solve(
const Eigen::MatrixBase<MatrixDerived> & x)
const
612 ReturnType
res(
self.constraintDim(),
x.cols());
626 return self.getInverseOperationalSpaceInertiaMatrix();
631 return self.getOperationalSpaceInertiaMatrix();
641 template<
typename VectorLike>
642 void updateDamping(
const Eigen::MatrixBase<VectorLike> & mus)
661 return self.constraintDim();
685 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
686 #include "pinocchio/algorithm/contact-cholesky.txx"
687 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
689 #include "pinocchio/algorithm/contact-cholesky.hxx"
691 #endif // ifndef __pinocchio_algorithm_contact_cholesky_hpp__