Namespaces | Functions
frames.hpp File Reference
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/frames.hxx"
Include dependency graph for frames.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 , typename Matrix6xLike >
void pinocchio::computeFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const Eigen::MatrixBase< Matrix6xLike > &J)
 Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6xLike >
void pinocchio::computeFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
 Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ForceTpl< Scalar, Options > pinocchio::computeSupportedForceByFrame (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
 Computes the force supported by a specific frame (given by frame_id) expressed in the LOCAL frame. The supported force corresponds to the sum of all the forces experienced after the given frame, i.e : More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
InertiaTpl< Scalar, Options > pinocchio::computeSupportedInertiaByFrame (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, bool with_subtree)
 Compute the inertia supported by a specific frame (given by frame_id) expressed in the LOCAL frame. The total supported inertia corresponds to the sum of all the inertia after the given frame, i.e : More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6xLike >
PINOCCHIO_DEPRECATED void pinocchio::frameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const Eigen::MatrixBase< Matrix6xLike > &J)
 This function is now deprecated and has been renamed computeFrameJacobian. This signature will be removed in future release of Pinocchio. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
PINOCCHIO_DEPRECATED void pinocchio::framesForwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Updates the position of each frame contained in the model. This function is now deprecated and has been renamed updateFramePlacements. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType >
void pinocchio::framesForwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
 First calls the forwardKinematics on the model, then computes the placement of each frame. /sa pinocchio::forwardKinematics. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
MotionTpl< Scalar, Options > pinocchio::getFrameAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
 Returns the spatial acceleration of the Frame 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::getFrameClassicalAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
 Returns the "classical" acceleration of the Frame 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, typename Matrix6xLike >
void pinocchio::getFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &J)
 Returns the jacobian of the frame expressed either expressed in the LOCAL frame coordinate system or in the WORLD coordinate system, depending on the value of rf. You must first call pinocchio::computeJointJacobians followed by pinocchio::framesForwardKinematics to update placement values in data structure. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xLike >
void pinocchio::getFrameJacobianTimeVariation (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &dJ)
 Computes the Jacobian time variation of a specific frame (given by frame_id) expressed either in the LOCAL frame. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
MotionTpl< Scalar, Options > pinocchio::getFrameVelocity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
 Returns the spatial velocity of the Frame 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>
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & pinocchio::updateFramePlacement (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id)
 Updates the placement of the given frame. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
void pinocchio::updateFramePlacements (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Updates the position of each frame contained in the model. More...
 


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