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> class JointCollectionTpl,
45  typename ConfigVectorType>
46  void forwardKinematics(
47  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
48  DataTpl<Scalar, Options, JointCollectionTpl> & data,
49  const Eigen::MatrixBase<ConfigVectorType> & q);
50 
64  template<
65  typename Scalar,
66  int Options,
67  template<typename, int> class JointCollectionTpl,
68  typename ConfigVectorType,
69  typename TangentVectorType>
70  void forwardKinematics(
71  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
72  DataTpl<Scalar, Options, JointCollectionTpl> & data,
73  const Eigen::MatrixBase<ConfigVectorType> & q,
74  const Eigen::MatrixBase<TangentVectorType> & v);
90  template<
91  typename Scalar,
92  int Options,
93  template<typename, int> class JointCollectionTpl,
94  typename ConfigVectorType,
95  typename TangentVectorType1,
96  typename TangentVectorType2>
97  void forwardKinematics(
98  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
99  DataTpl<Scalar, Options, JointCollectionTpl> & data,
100  const Eigen::MatrixBase<ConfigVectorType> & q,
101  const Eigen::MatrixBase<TangentVectorType1> & v,
102  const Eigen::MatrixBase<TangentVectorType2> & a);
103 
118  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
119  MotionTpl<Scalar, Options> getVelocity(
120  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
121  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
122  const JointIndex jointId,
123  const ReferenceFrame rf = LOCAL);
124 
139  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
140  MotionTpl<Scalar, Options> getAcceleration(
141  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
142  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
143  const JointIndex jointId,
144  const ReferenceFrame rf = LOCAL);
145 
161  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
162  MotionTpl<Scalar, Options> getClassicalAcceleration(
163  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
164  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
165  const JointIndex jointId,
166  const ReferenceFrame rf = LOCAL);
167 
168 } // namespace pinocchio
169 
170 /* --- Details -------------------------------------------------------------------- */
171 /* --- Details -------------------------------------------------------------------- */
172 /* --- Details -------------------------------------------------------------------- */
173 #include "pinocchio/algorithm/kinematics.hxx"
174 
175 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
176  #include "pinocchio/algorithm/kinematics.txx"
177 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
178 
179 #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:1082
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:1083
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:1084
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:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:46