Namespaces | Functions
contact-inverse-dynamics.hpp File Reference
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp"
#include "pinocchio/algorithm/rnea.hpp"
#include <boost/optional/optional.hpp>
#include <pinocchio/algorithm/contact-cholesky.hpp>
#include <pinocchio/algorithm/contact-jacobian.hpp>
#include "pinocchio/algorithm/proximal.hpp"
#include <boost/optional.hpp>
Include dependency graph for contact-inverse-dynamics.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 pinocchio
 Main pinocchio namespace.
 

Functions

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename VectorLikeC , class ConstraintModelAllocator , class ConstraintDataAllocator , class CoulombFrictionConelAllocator , typename VectorLikeR , typename VectorLikeGamma , typename VectorLikeImp >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::computeContactImpulses (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< VectorLikeC > &c_ref, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeImp > &impulse_guess=boost::none)
 Compute the contact impulses given a target velocity of contact points. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ConstraintModelAllocator , class ConstraintDataAllocator , class CoulombFrictionConelAllocator , typename VectorLikeR , typename VectorLikeGamma , typename VectorLikeLam >
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & pinocchio::contactInverseDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, Scalar dt, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeLam > &lambda_guess=boost::none)
 The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the presence of contacts, aka the joint torques according to the current state of the system and the desired joint accelerations. More...
 


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:41