src/multibody/fwd.hpp
Go to the documentation of this file.
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 
34 
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__
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
Refers to the quantities related to the 2nd-order kinematics (joint accelerations, center of mass acceleration, etc.).
ModelTpl< double > Model
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
FrameTpl< double > Frame
ReferenceFrame
List of Reference Frames supported by Pinocchio.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
KinematicLevel
List of Kinematics Level supported by Pinocchio.
DataTpl< double > Data
Refers to the quantities related to the 1st-order kinematics (joint velocities, center of mass veloci...
CRTP class describing the API of the checkers.
Definition: check.hpp:22
Main pinocchio namespace.
Definition: timings.cpp:30
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
std::size_t Index
Refers to the quantities related to the 0-order kinematics (joint placements, center of mass position...


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