src/algorithm/regressor.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022-2024 INRIA
3 //
4 
6 
7 namespace pinocchio
8 {
9 
10  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeJointKinematicRegressor<
13  JointCollectionDefaultTpl,
15  const context::Model &,
16  const context::Data &,
17  const JointIndex,
18  const ReferenceFrame,
19  const SE3Tpl<context::Scalar, context::Options> &,
20  const Eigen::MatrixBase<context::Matrix6xs> &);
21 
22  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs
23  computeJointKinematicRegressor<context::Scalar, context::Options, JointCollectionDefaultTpl>(
24  const context::Model &,
25  const context::Data &,
26  const JointIndex,
27  const ReferenceFrame,
28  const SE3Tpl<context::Scalar, context::Options> &);
29 
30  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeJointKinematicRegressor<
33  JointCollectionDefaultTpl,
35  const context::Model &,
36  const context::Data &,
37  const JointIndex,
38  const ReferenceFrame,
39  const Eigen::MatrixBase<context::Matrix6xs> &);
40 
41  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs
42  computeJointKinematicRegressor<context::Scalar, context::Options, JointCollectionDefaultTpl>(
43  const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame);
44 
45  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeFrameKinematicRegressor<
48  JointCollectionDefaultTpl,
50  const context::Model &,
51  context::Data &,
52  const FrameIndex,
53  const ReferenceFrame,
54  const Eigen::MatrixBase<context::Matrix6xs> &);
55 
56  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs
57  computeFrameKinematicRegressor<context::Scalar, context::Options, JointCollectionDefaultTpl>(
58  const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame);
59 
60  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix3x &
64  JointCollectionDefaultTpl,
66  const context::Model &, context::Data &, const Eigen::MatrixBase<context::VectorXs> &);
67 
68  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void
69  bodyRegressor<context::Motion, context::Motion, context::BodyRegressorType>(
70  const MotionDense<context::Motion> &,
71  const MotionDense<context::Motion> &,
72  const Eigen::MatrixBase<context::BodyRegressorType> &);
73 
74  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType
75  bodyRegressor<context::Motion, context::Motion>(
76  const MotionDense<context::Motion> &, const MotionDense<context::Motion> &);
77 
78  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType &
79  jointBodyRegressor<context::Scalar, context::Options, JointCollectionDefaultTpl>(
81 
82  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType &
83  frameBodyRegressor<context::Scalar, context::Options, JointCollectionDefaultTpl>(
85 
86  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs &
90  JointCollectionDefaultTpl,
94  const context::Model &,
95  context::Data &,
96  const Eigen::MatrixBase<context::VectorXs> &,
97  const Eigen::MatrixBase<context::VectorXs> &,
98  const Eigen::MatrixBase<context::VectorXs> &);
99 
100  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const context::Data::RowVectorXs &
101  computeKineticEnergyRegressor<
104  JointCollectionDefaultTpl,
107  const context::Model &,
108  context::Data &,
109  const Eigen::MatrixBase<context::VectorXs> &,
110  const Eigen::MatrixBase<context::VectorXs> &);
111 
112  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const context::Data::RowVectorXs &
116  JointCollectionDefaultTpl,
118  const context::Model &, context::Data &, const Eigen::MatrixBase<context::VectorXs> &);
119 
120 } // namespace pinocchio
pinocchio::context::Model
ModelTpl< Scalar, Options > Model
Definition: context/generic.hpp:56
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::computeJointTorqueRegressor
DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeJointTorqueRegressor(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 the joint torque regressor that links the joint torque to the dynamic parameters of each lin...
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::context::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: context/generic.hpp:49
pinocchio::context::BodyRegressorType
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
Definition: context/generic.hpp:54
regressor.hpp
pinocchio::computePotentialEnergyRegressor
const DataTpl< Scalar, Options, JointCollectionTpl >::RowVectorXs & computePotentialEnergyRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
pinocchio::context::Options
@ Options
Definition: context/generic.hpp:45
pinocchio::computeJointKinematicRegressor
void computeJointKinematicRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame rf, const SE3Tpl< Scalar, Options > &placement, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor)
pinocchio::computeFrameKinematicRegressor
void computeFrameKinematicRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor)
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::computeStaticRegressor
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & computeStaticRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the static regressor that links the center of mass positions of all the links to the center ...
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::DataTpl::RowVectorXs
Eigen::Matrix< Scalar, 1, Eigen::Dynamic, Options|Eigen::RowMajor > RowVectorXs
Definition: multibody/data.hpp:76
pinocchio::context::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
Definition: context/generic.hpp:52
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:40