jacobian.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  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const context::Matrix6xs &
15  JointCollectionDefaultTpl,
16  Eigen::Ref<const context::VectorXs>>(
17  const context::Model &,
18  context::Data &,
19  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &);
20  } // namespace impl
21  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const context::Matrix6xs &
22  computeJointJacobians<context::Scalar, context::Options, JointCollectionDefaultTpl>(
23  const context::Model &, context::Data &);
24  namespace impl
25  {
26  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getJointJacobian<
29  JointCollectionDefaultTpl,
30  Eigen::Ref<context::Matrix6xs>>(
31  const context::Model &,
32  const context::Data &,
33  const JointIndex,
34  const ReferenceFrame,
35  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &);
36  } // namespace impl
37  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs
38  getJointJacobian<context::Scalar, context::Options, JointCollectionDefaultTpl>(
39  const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame);
40  namespace impl
41  {
42  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeJointJacobian<
45  JointCollectionDefaultTpl,
46  Eigen::Ref<const context::VectorXs>,
47  Eigen::Ref<context::Matrix6xs>>(
48  const context::Model &,
49  context::Data &,
50  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
51  const JointIndex,
52  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &);
53 
54  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const context::Matrix6xs &
58  JointCollectionDefaultTpl,
59  Eigen::Ref<const context::VectorXs>,
60  Eigen::Ref<const context::VectorXs>>(
61  const context::Model &,
62  context::Data &,
63  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &,
64  const Eigen::MatrixBase<Eigen::Ref<const context::VectorXs>> &);
65 
66  template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getJointJacobianTimeVariation<
69  JointCollectionDefaultTpl,
70  Eigen::Ref<context::Matrix6xs>>(
71  const context::Model &,
72  const context::Data &,
73  const JointIndex,
74  const ReferenceFrame,
75  const Eigen::MatrixBase<Eigen::Ref<context::Matrix6xs>> &);
76  } // namespace impl
77 
78 } // namespace pinocchio
pinocchio::context::Model
ModelTpl< Scalar, Options > Model
Definition: context/generic.hpp:56
pinocchio::getJointJacobianTimeVariation
void getJointJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &dJ)
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (r...
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::computeJointJacobiansTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
pinocchio::computeJointJacobians
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame....
pinocchio::getJointJacobian
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame opt...
pinocchio::context::Options
@ Options
Definition: context/generic.hpp:45
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::computeJointJacobian
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
jacobian.hpp
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:38