pinocchio  2.6.20
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
fwd.hpp
1 //
2 // Copyright (c) 2017-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_multibody_fwd_hpp__
6 #define __pinocchio_multibody_fwd_hpp__
7 
8 #include "pinocchio/fwd.hpp"
9 
10 #include "pinocchio/multibody/joint/fwd.hpp"
11 
12 namespace pinocchio
13 {
14 
20  template<typename Scalar, int Options=0> struct FrameTpl;
21 
22  template<typename Scalar, int Options = 0, template<typename S, int O> class JointCollectionTpl = JointCollectionDefaultTpl>
23  struct ModelTpl;
24  template<typename Scalar, int Options = 0, template<typename S, int O> class JointCollectionTpl = JointCollectionDefaultTpl>
25  struct DataTpl;
26 
27  typedef std::size_t Index;
28  typedef Index JointIndex;
29  typedef Index GeomIndex;
30  typedef Index FrameIndex;
31  typedef Index PairIndex;
32 
33  typedef FrameTpl<double> Frame;
34 
35  typedef ModelTpl<double> Model;
36  typedef DataTpl<double> Data;
37 
38  struct GeometryModel;
39  struct GeometryData;
40 
45  {
46  WORLD = 0,
47  LOCAL = 1,
49  };
50 
55  {
56  POSITION = 0,
57  VELOCITY = 1,
59  };
60 
64  // end of group multibody
65 
66  // Forward declaration needed for Model::check
67  template<class D> struct AlgorithmCheckerBase;
68 
69 } // namespace pinocchio
70 
71 #endif // #ifndef __pinocchio_multibody_fwd_hpp__
pinocchio::KinematicLevel
KinematicLevel
List of Kinematics Level supported by Pinocchio.
Definition: fwd.hpp:54
pinocchio::DataTpl
Definition: data.hpp:29
pinocchio::LOCAL_WORLD_ALIGNED
@ LOCAL_WORLD_ALIGNED
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint,...
Definition: fwd.hpp:48
pinocchio::ReferenceFrame
ReferenceFrame
List of Reference Frames supported by Pinocchio.
Definition: fwd.hpp:44
pinocchio::WORLD
@ WORLD
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
Definition: fwd.hpp:46
pinocchio::GeometryData
Definition: geometry.hpp:187
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: frame.hpp:41
pinocchio::POSITION
@ POSITION
Refers to the quantities related to the 0-order kinematics (joint placements, center of mass position...
Definition: fwd.hpp:56
pinocchio::VELOCITY
@ VELOCITY
Refers to the quantities related to the 1st-order kinematics (joint velocities, center of mass veloci...
Definition: fwd.hpp:57
pinocchio::LOCAL
@ LOCAL
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint,...
Definition: fwd.hpp:47
pinocchio::GeometryModel
Definition: geometry.hpp:22
pinocchio::JointCollectionDefaultTpl
Definition: fwd.hpp:81
pinocchio::ModelTpl
Definition: fwd.hpp:23
pinocchio::ACCELERATION
@ ACCELERATION
Refers to the quantities related to the 2nd-order kinematics (joint accelerations,...
Definition: fwd.hpp:58
pinocchio
Main pinocchio namespace.
Definition: treeview.dox:11