src/algorithm/frames.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
4 
6 
7 namespace pinocchio
8 {
9 
10  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
11  updateFramePlacements<context::Scalar, context::Options, JointCollectionDefaultTpl>(
12  const context::Model &, context::Data &);
13 
14  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const
15  SE3Tpl<context::Scalar, context::Options> &
16  updateFramePlacement<context::Scalar, context::Options, JointCollectionDefaultTpl>(
17  const context::Model &, context::Data &, const FrameIndex);
18 
19  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void framesForwardKinematics<
22  JointCollectionDefaultTpl,
24  const context::Model &, context::Data &, const Eigen::MatrixBase<context::VectorXs> &);
25 
26  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
27  MotionTpl<context::Scalar, context::Options>
28  getFrameVelocity<context::Scalar, context::Options, JointCollectionDefaultTpl>(
29  const context::Model &,
30  const context::Data &,
31  const JointIndex,
32  const SE3Tpl<context::Scalar, context::Options> &,
33  const ReferenceFrame);
34 
35  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
36  MotionTpl<context::Scalar, context::Options>
37  getFrameVelocity<context::Scalar, context::Options, JointCollectionDefaultTpl>(
38  const context::Model &, const context::Data &, const FrameIndex, const ReferenceFrame);
39 
40  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
41  MotionTpl<context::Scalar, context::Options>
42  getFrameAcceleration<context::Scalar, context::Options, JointCollectionDefaultTpl>(
43  const context::Model &,
44  const context::Data &,
45  const JointIndex,
46  const SE3Tpl<context::Scalar, context::Options> &,
47  const ReferenceFrame);
48 
49  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
50  MotionTpl<context::Scalar, context::Options>
51  getFrameAcceleration<context::Scalar, context::Options, JointCollectionDefaultTpl>(
52  const context::Model &, const context::Data &, const FrameIndex, const ReferenceFrame);
53 
54  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
55  MotionTpl<context::Scalar, context::Options>
56  getFrameClassicalAcceleration<context::Scalar, context::Options, JointCollectionDefaultTpl>(
57  const context::Model &,
58  const context::Data &,
59  const JointIndex,
60  const SE3Tpl<context::Scalar, context::Options> &,
61  const ReferenceFrame);
62 
63  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
64  MotionTpl<context::Scalar, context::Options>
65  getFrameClassicalAcceleration<context::Scalar, context::Options, JointCollectionDefaultTpl>(
66  const context::Model &, const context::Data &, const FrameIndex, const ReferenceFrame);
67 
68  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getFrameJacobian<
71  JointCollectionDefaultTpl,
73  const context::Model &,
74  context::Data &,
75  const JointIndex,
76  const SE3Tpl<context::Scalar, context::Options> &,
77  const ReferenceFrame,
78  const Eigen::MatrixBase<context::Matrix6xs> &);
79 
80  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs
81  getFrameJacobian<context::Scalar, context::Options, JointCollectionDefaultTpl>(
82  const context::Model &,
83  context::Data &,
84  const JointIndex,
85  const SE3Tpl<context::Scalar, context::Options> &,
86  const ReferenceFrame);
87 
88  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getFrameJacobian<
91  JointCollectionDefaultTpl,
93  const context::Model &,
94  context::Data &,
95  const FrameIndex,
96  const ReferenceFrame,
97  const Eigen::MatrixBase<context::Matrix6xs> &);
98 
99  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs
100  getFrameJacobian<context::Scalar, context::Options, JointCollectionDefaultTpl>(
101  const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame);
102 
103  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeFrameJacobian<
106  JointCollectionDefaultTpl,
109  const context::Model &,
110  context::Data &,
111  const Eigen::MatrixBase<context::VectorXs> &,
112  const FrameIndex,
113  const ReferenceFrame,
114  const Eigen::MatrixBase<context::Matrix6xs> &);
115 
116  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeFrameJacobian<
119  JointCollectionDefaultTpl,
122  const context::Model &,
123  context::Data &,
124  const Eigen::MatrixBase<context::VectorXs> &,
125  const FrameIndex,
126  const Eigen::MatrixBase<context::Matrix6xs> &);
127 
128  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getFrameJacobianTimeVariation<
131  JointCollectionDefaultTpl,
133  const context::Model &,
134  context::Data &,
135  const FrameIndex,
136  const ReferenceFrame,
137  const Eigen::MatrixBase<context::Matrix6xs> &);
138 } // namespace pinocchio
pinocchio::context::Model
ModelTpl< Scalar, Options > Model
Definition: context/generic.hpp:56
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
frames.hpp
pinocchio::getFrameJacobian
void getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame,...
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::computeFrameJacobian
void computeFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J)
Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument.
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::context::Options
@ Options
Definition: context/generic.hpp:45
pinocchio::framesForwardKinematics
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame....
pinocchio::context::Matrix6xs
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6xs
Definition: context/generic.hpp:48
pinocchio::context::Data
DataTpl< Scalar, Options > Data
Definition: context/generic.hpp:57
pinocchio::getFrameJacobianTimeVariation
void getFrameJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &dJ)
Computes the Jacobian time variation of a specific frame (given by frame_id) expressed either in the ...
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
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:37