kinematics.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_kinematics_hpp__
6 #define __pinocchio_kinematics_hpp__
7 
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/data.hpp"
10 
11 namespace pinocchio
12 {
13 
26  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
27  inline void updateGlobalPlacements(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
28  DataTpl<Scalar,Options,JointCollectionTpl> & data);
29 
40  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
41  inline void forwardKinematics(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
42  DataTpl<Scalar,Options,JointCollectionTpl> & data,
43  const Eigen::MatrixBase<ConfigVectorType> & q);
44 
57  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType>
58  inline void forwardKinematics(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
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>
77  inline void forwardKinematics(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
78  DataTpl<Scalar,Options,JointCollectionTpl> & data,
79  const Eigen::MatrixBase<ConfigVectorType> & q,
80  const Eigen::MatrixBase<TangentVectorType1> & v,
81  const Eigen::MatrixBase<TangentVectorType2> & a);
82 
96  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
97  inline MotionTpl<Scalar, Options>
98  getVelocity(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
99  const DataTpl<Scalar,Options,JointCollectionTpl> & data,
100  const JointIndex jointId,
101  const ReferenceFrame rf = LOCAL);
102 
116  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
117  inline MotionTpl<Scalar, Options>
118  getAcceleration(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
119  const DataTpl<Scalar,Options,JointCollectionTpl> & data,
120  const JointIndex jointId,
121  const ReferenceFrame rf = LOCAL);
122 
137  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
138  inline MotionTpl<Scalar, Options>
139  getClassicalAcceleration(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
140  const DataTpl<Scalar,Options,JointCollectionTpl> & data,
141  const JointIndex jointId,
142  const ReferenceFrame rf = LOCAL);
143 
144 } // namespace pinocchio
145 
146 /* --- Details -------------------------------------------------------------------- */
147 /* --- Details -------------------------------------------------------------------- */
148 /* --- Details -------------------------------------------------------------------- */
149 #include "pinocchio/algorithm/kinematics.hxx"
150 
151 
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.
Definition: timings.cpp:30
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.


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04