Go to the documentation of this file.
    5 #ifndef __pinocchio_algorithm_jacobian_hpp__ 
    6 #define __pinocchio_algorithm_jacobian_hpp__ 
   35     template<
typename, 
int> 
class JointCollectionTpl,
 
   38     const ModelTpl<Scalar, Options, JointCollectionTpl> & 
model,
 
   39     DataTpl<Scalar, Options, JointCollectionTpl> & 
data,
 
   40     const Eigen::MatrixBase<ConfigVectorType> & 
q);
 
   59   template<
typename Scalar, 
int Options, 
template<
typename, 
int> 
class JointCollectionTpl>
 
   61     const ModelTpl<Scalar, Options, JointCollectionTpl> & 
model,
 
   62     DataTpl<Scalar, Options, JointCollectionTpl> & 
data);
 
  105     template<
typename, 
int> 
class JointCollectionTpl,
 
  106     typename Matrix6Like>
 
  108     const ModelTpl<Scalar, Options, JointCollectionTpl> & 
model,
 
  109     const DataTpl<Scalar, Options, JointCollectionTpl> & 
data,
 
  112     const Eigen::MatrixBase<Matrix6Like> & 
J);
 
  126   template<
typename Scalar, 
int Options, 
template<
typename, 
int> 
class JointCollectionTpl>
 
  133     typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> ReturnType;
 
  134     ReturnType 
res(ReturnType::Zero(6, 
model.nv));
 
  170     template<
typename, 
int> 
class JointCollectionTpl,
 
  172     typename Matrix6Like>
 
  174     const ModelTpl<Scalar, Options, JointCollectionTpl> & 
model,
 
  175     DataTpl<Scalar, Options, JointCollectionTpl> & 
data,
 
  176     const Eigen::MatrixBase<ConfigVectorType> & 
q,
 
  178     const Eigen::MatrixBase<Matrix6Like> & 
J);
 
  199     template<
typename, 
int> 
class JointCollectionTpl,
 
  204     const ModelTpl<Scalar, Options, JointCollectionTpl> & 
model,
 
  205     DataTpl<Scalar, Options, JointCollectionTpl> & 
data,
 
  206     const Eigen::MatrixBase<ConfigVectorType> & 
q,
 
  207     const Eigen::MatrixBase<TangentVectorType> & 
v);
 
  228     template<
typename, 
int> 
class JointCollectionTpl,
 
  229     typename Matrix6Like>
 
  231     const ModelTpl<Scalar, Options, JointCollectionTpl> & 
model,
 
  232     const DataTpl<Scalar, Options, JointCollectionTpl> & 
data,
 
  235     const Eigen::MatrixBase<Matrix6Like> & dJ);
 
  243 #include "pinocchio/algorithm/jacobian.hxx" 
  245 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION 
  246   #include "pinocchio/algorithm/jacobian.txx" 
  247 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION 
  249 #endif // ifndef __pinocchio_algorithm_jacobian_hpp__ 
  
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...
ReferenceFrame
Various conventions to express the velocity of a moving frame.
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...
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....
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...
Model::ConfigVectorType ConfigVectorType
Model::TangentVectorType TangentVectorType
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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...
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:18