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 
10 
11 namespace pinocchio
12 {
13 
26  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
28  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
29  DataTpl<Scalar, Options, JointCollectionTpl> & data);
30 
41  template<
42  typename Scalar,
43  int Options,
44  template<typename, int>
45  class JointCollectionTpl,
46  typename ConfigVectorType>
47  void forwardKinematics(
48  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
49  DataTpl<Scalar, Options, JointCollectionTpl> & data,
50  const Eigen::MatrixBase<ConfigVectorType> & q);
51 
65  template<
66  typename Scalar,
67  int Options,
68  template<typename, int>
69  class JointCollectionTpl,
70  typename ConfigVectorType,
71  typename TangentVectorType>
72  void forwardKinematics(
73  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
74  DataTpl<Scalar, Options, JointCollectionTpl> & data,
75  const Eigen::MatrixBase<ConfigVectorType> & q,
76  const Eigen::MatrixBase<TangentVectorType> & v);
92  template<
93  typename Scalar,
94  int Options,
95  template<typename, int>
96  class JointCollectionTpl,
97  typename ConfigVectorType,
98  typename TangentVectorType1,
99  typename TangentVectorType2>
100  void forwardKinematics(
101  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
102  DataTpl<Scalar, Options, JointCollectionTpl> & data,
103  const Eigen::MatrixBase<ConfigVectorType> & q,
104  const Eigen::MatrixBase<TangentVectorType1> & v,
105  const Eigen::MatrixBase<TangentVectorType2> & a);
106 
121  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
122  MotionTpl<Scalar, Options> getVelocity(
123  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
124  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
125  const JointIndex jointId,
126  const ReferenceFrame rf = LOCAL);
127 
142  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
143  MotionTpl<Scalar, Options> getAcceleration(
144  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
145  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
146  const JointIndex jointId,
147  const ReferenceFrame rf = LOCAL);
148 
164  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
165  MotionTpl<Scalar, Options> getClassicalAcceleration(
166  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
167  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
168  const JointIndex jointId,
169  const ReferenceFrame rf = LOCAL);
170 
171 } // namespace pinocchio
172 
173 /* --- Details -------------------------------------------------------------------- */
174 /* --- Details -------------------------------------------------------------------- */
175 /* --- Details -------------------------------------------------------------------- */
176 #include "pinocchio/algorithm/kinematics.hxx"
177 
178 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
179  #include "pinocchio/algorithm/kinematics.txx"
180 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
181 
182 #endif // ifndef __pinocchio_kinematics_hpp__
pinocchio::forwardKinematics
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.
pinocchio::updateGlobalPlacements
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.
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
data.hpp
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::getVelocity
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....
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::getClassicalAcceleration
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....
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::getAcceleration
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....
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Fri Jun 7 2024 02:40:48