5 #ifndef __pinocchio_kinematics_hpp__ 6 #define __pinocchio_kinematics_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/data.hpp" 26 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
28 DataTpl<Scalar,Options,JointCollectionTpl> & data);
40 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType>
42 DataTpl<Scalar,Options,JointCollectionTpl> & data,
43 const Eigen::MatrixBase<ConfigVectorType> &
q);
57 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType>
59 DataTpl<Scalar,Options,JointCollectionTpl> & data,
60 const Eigen::MatrixBase<ConfigVectorType> &
q,
61 const Eigen::MatrixBase<TangentVectorType> &
v);
76 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2>
78 DataTpl<Scalar,Options,JointCollectionTpl> & data,
79 const Eigen::MatrixBase<ConfigVectorType> &
q,
80 const Eigen::MatrixBase<TangentVectorType1> &
v,
81 const Eigen::MatrixBase<TangentVectorType2> & a);
96 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
97 inline MotionTpl<Scalar, Options>
99 const DataTpl<Scalar,Options,JointCollectionTpl> & data,
116 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
117 inline MotionTpl<Scalar, Options>
119 const DataTpl<Scalar,Options,JointCollectionTpl> & data,
137 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
138 inline MotionTpl<Scalar, Options>
140 const DataTpl<Scalar,Options,JointCollectionTpl> & data,
149 #include "pinocchio/algorithm/kinematics.hxx" 152 #endif // ifndef __pinocchio_kinematics_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
ReferenceFrame
List of Reference Frames supported by Pinocchio.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
void 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.
MotionTpl< Scalar, Options > 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...
void 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...
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
Main pinocchio namespace.
MotionTpl< Scalar, Options > 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.
JointCollectionTpl & model
MotionTpl< Scalar, Options > 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.