Namespaces | Functions
kinematics.hpp File Reference
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/kinematics.hxx"
Include dependency graph for kinematics.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 ConfigVectorType >
void pinocchio::forwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
 Update the joint placements according to the current joint configuration. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType >
void pinocchio::forwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
 Update the joint placements and spatial velocities according to the current joint configuration and velocity. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 >
void pinocchio::forwardKinematics (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)
 Update the joint placements, spatial velocities and spatial accelerations according to the current joint configuration, velocity and acceleration. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
MotionTpl< Scalar, Options > pinocchio::getAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
 Returns the spatial acceleration of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
MotionTpl< Scalar, Options > pinocchio::getClassicalAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
 Returns the "classical" acceleration of the joint expressed in the desired reference frame. This is different from the "spatial" acceleration in that centrifugal effects are accounted for. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
MotionTpl< Scalar, Options > pinocchio::getVelocity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
 Returns the spatial velocity of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
void pinocchio::updateGlobalPlacements (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Update the global placement of the joints oMi according to the relative placements of the joints. More...
 


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:00