src/algorithm/kinematics-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
4 
6 
7 namespace pinocchio
8 {
9  namespace impl
10  {
11 
12  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
16  JointCollectionDefaultTpl,
17  Eigen::Ref<const context::VectorXs>,
18  Eigen::Ref<const context::VectorXs>,
19  Eigen::Ref<const context::VectorXs>>(
20  const context::Model &,
21  context::Data &,
22  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
23  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
24  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &);
25 
26  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getJointVelocityDerivatives<
29  JointCollectionDefaultTpl,
30  Eigen::Ref<context::Matrix6xs>,
31  Eigen::Ref<context::Matrix6xs>>(
32  const context::Model &,
33  const context::Data &,
34  const JointIndex,
35  const ReferenceFrame,
36  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
37  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &);
38 
39  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
43  JointCollectionDefaultTpl,
44  Eigen::Ref<context::Matrix6xs>,
45  Eigen::Ref<context::Matrix6xs>,
46  Eigen::Ref<context::Matrix6xs>,
47  Eigen::Ref<context::Matrix6xs>>(
48  const context::Model &,
49  const context::Data &,
50  const JointIndex,
51  const ReferenceFrame,
52  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
53  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
54  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
55  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &);
56 
57  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
61  JointCollectionDefaultTpl,
62  Eigen::Ref<context::Matrix6xs>,
63  Eigen::Ref<context::Matrix6xs>,
64  Eigen::Ref<context::Matrix6xs>,
65  Eigen::Ref<context::Matrix6xs>,
66  Eigen::Ref<context::Matrix6xs>>(
67  const context::Model &,
68  const context::Data &,
69  const JointIndex,
70  const ReferenceFrame,
71  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
72  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
73  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
74  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &,
75  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &);
76 
77  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getPointVelocityDerivatives<
80  JointCollectionDefaultTpl,
81  Eigen::Ref<context::Matrix3x>,
82  Eigen::Ref<context::Matrix3x>>(
83  const context::Model &,
84  const context::Data &,
85  const JointIndex,
86  const SE3Tpl<context::Scalar, context::Options> &,
87  const ReferenceFrame,
88  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
89  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &);
90 
91  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
95  JointCollectionDefaultTpl,
96  Eigen::Ref<context::Matrix3x>,
97  Eigen::Ref<context::Matrix3x>,
98  Eigen::Ref<context::Matrix3x>,
99  Eigen::Ref<context::Matrix3x>>(
100  const context::Model &,
101  const context::Data &,
102  const JointIndex,
103  const SE3Tpl<context::Scalar, context::Options> &,
104  const ReferenceFrame,
105  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
106  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
107  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
108  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &);
109 
110  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
114  JointCollectionDefaultTpl,
115  Eigen::Ref<context::Matrix3x>,
116  Eigen::Ref<context::Matrix3x>,
117  Eigen::Ref<context::Matrix3x>,
118  Eigen::Ref<context::Matrix3x>,
119  Eigen::Ref<context::Matrix3x>>(
120  const context::Model &,
121  const context::Data &,
122  const JointIndex,
123  const SE3Tpl<context::Scalar, context::Options> &,
124  const ReferenceFrame,
125  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
126  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
127  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
128  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &,
129  const Eigen::MatrixBase<Eigen::Ref<context::Matrix3x>> &);
130  } // namespace impl
131 
132  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
133  computeJointKinematicHessians<context::Scalar, context::Options, JointCollectionDefaultTpl>(
134  const context::Model &, context::Data &);
135 
136  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeJointKinematicHessians<
139  JointCollectionDefaultTpl,
141  const context::Model &, context::Data &, const Eigen::MatrixBase<context::VectorXs> &);
142 
143  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
144  getJointKinematicHessian<context::Scalar, context::Options, JointCollectionDefaultTpl>(
145  const context::Model &,
146  const context::Data &,
147  const JointIndex,
148  const ReferenceFrame,
149  Tensor<context::Scalar, 3, context::Options> &);
150 
151  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
152  Tensor<context::Scalar, 3, context::Options>
153  getJointKinematicHessian<context::Scalar, context::Options, JointCollectionDefaultTpl>(
154  const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame);
155 } // namespace pinocchio
pinocchio::context::Model
ModelTpl< Scalar, Options > Model
Definition: context/generic.hpp:56
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::getPointClassicAccelerationDerivatives
void getPointClassicAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &a_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut3 > &a_point_partial_dv, const Eigen::MatrixBase< Matrix3xOut4 > &a_point_partial_da)
Computes the partial derivatives of the classic acceleration of a point given by its placement inform...
pinocchio::computeJointKinematicHessians
void computeJointKinematicHessians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes all the terms required to compute the second order derivatives of the placement information,...
pinocchio::getJointAccelerationDerivatives
void getJointAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_da)
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint conf...
pinocchio::computeForwardKinematicsDerivatives
void computeForwardKinematicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acc...
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::getJointVelocityDerivatives
void getJointVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
Computes the partial derivaties of the spatial velocity of a given with respect to the joint configur...
pinocchio::context::Options
@ Options
Definition: context/generic.hpp:45
pinocchio::context::Data
DataTpl< Scalar, Options > Data
Definition: context/generic.hpp:57
kinematics-derivatives.hpp
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::getPointVelocityDerivatives
void getPointVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &v_point_partial_dv)
Computes the partial derivatives of the velocity of a point given by its placement information w....
pinocchio::context::Scalar
PINOCCHIO_SCALAR_TYPE Scalar
Definition: context/generic.hpp:42
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:39