jacobian.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_jacobian_hpp__
6 #define __pinocchio_algorithm_jacobian_hpp__
7 
10 
11 namespace pinocchio
12 {
32  template<
33  typename Scalar,
34  int Options,
35  template<typename, int>
36  class JointCollectionTpl,
37  typename ConfigVectorType>
39  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
40  DataTpl<Scalar, Options, JointCollectionTpl> & data,
41  const Eigen::MatrixBase<ConfigVectorType> & q);
42 
60  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
62  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
63  DataTpl<Scalar, Options, JointCollectionTpl> & data);
64 
103  template<
104  typename Scalar,
105  int Options,
106  template<typename, int>
107  class JointCollectionTpl,
108  typename Matrix6Like>
109  void getJointJacobian(
110  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
111  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
112  const JointIndex joint_id,
113  const ReferenceFrame reference_frame,
114  const Eigen::MatrixBase<Matrix6Like> & J);
128  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
129  Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> getJointJacobian(
132  const JointIndex joint_id,
133  const ReferenceFrame reference_frame)
134  {
135  typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> ReturnType;
136  ReturnType res(ReturnType::Zero(6, model.nv));
137 
138  getJointJacobian(model, data, joint_id, reference_frame, res);
139  return res;
140  }
141 
169  template<
170  typename Scalar,
171  int Options,
172  template<typename, int>
173  class JointCollectionTpl,
174  typename ConfigVectorType,
175  typename Matrix6Like>
177  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
178  DataTpl<Scalar, Options, JointCollectionTpl> & data,
179  const Eigen::MatrixBase<ConfigVectorType> & q,
180  const JointIndex joint_id,
181  const Eigen::MatrixBase<Matrix6Like> & J);
182 
199  template<
200  typename Scalar,
201  int Options,
202  template<typename, int>
203  class JointCollectionTpl,
204  typename ConfigVectorType,
205  typename TangentVectorType>
208  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
209  DataTpl<Scalar, Options, JointCollectionTpl> & data,
210  const Eigen::MatrixBase<ConfigVectorType> & q,
211  const Eigen::MatrixBase<TangentVectorType> & v);
212 
229  template<
230  typename Scalar,
231  int Options,
232  template<typename, int>
233  class JointCollectionTpl,
234  typename Matrix6Like>
236  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
237  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
238  const JointIndex joint_id,
239  const ReferenceFrame reference_frame,
240  const Eigen::MatrixBase<Matrix6Like> & dJ);
241 
242 } // namespace pinocchio
243 
244 /* --- Details -------------------------------------------------------------------- */
245 /* --- Details -------------------------------------------------------------------- */
246 /* --- Details -------------------------------------------------------------------- */
247 
248 #include "pinocchio/algorithm/jacobian.hxx"
249 
250 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
251  #include "pinocchio/algorithm/jacobian.txx"
252 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
253 
254 #endif // ifndef __pinocchio_algorithm_jacobian_hpp__
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::DataTpl
Definition: context/generic.hpp:25
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
inverse-kinematics.J
J
Definition: inverse-kinematics.py:31
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
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::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
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...
data.hpp
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
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
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:92
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:47