jacobian.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_jacobian_hpp__
6 #define __pinocchio_jacobian_hpp__
7 
8 #include "pinocchio/multibody/fwd.hpp"
9 #include "pinocchio/multibody/model.hpp"
10 #include "pinocchio/multibody/data.hpp"
11 
12 namespace pinocchio
13 {
29  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
31  computeJointJacobians(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
32  DataTpl<Scalar,Options,JointCollectionTpl> & data,
33  const Eigen::MatrixBase<ConfigVectorType> & q);
34 
48  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
50  computeJointJacobians(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
51  DataTpl<Scalar,Options,JointCollectionTpl> & data);
52 
66  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename Matrix6Like>
67  inline void getJointJacobian(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
68  const DataTpl<Scalar,Options,JointCollectionTpl> & data,
70  const ReferenceFrame rf,
71  const Eigen::MatrixBase<Matrix6Like> & J);
72 
93  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename Matrix6Like>
94  inline void computeJointJacobian(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
95  DataTpl<Scalar,Options,JointCollectionTpl> & data,
96  const Eigen::MatrixBase<ConfigVectorType> & q,
97  const JointIndex jointId,
98  const Eigen::MatrixBase<Matrix6Like> & J);
99 
105  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename Matrix6Like>
106  PINOCCHIO_DEPRECATED
109  const Eigen::MatrixBase<ConfigVectorType> & q,
110  const JointIndex jointId,
111  const Eigen::MatrixBase<Matrix6Like> & J)
112  {
113  computeJointJacobian(model,data,q,jointId,PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,J));
114  }
115 
131  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType>
135  const Eigen::MatrixBase<ConfigVectorType> & q,
136  const Eigen::MatrixBase<TangentVectorType> & v);
137 
151  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename Matrix6Like>
154  const JointIndex jointId,
155  const ReferenceFrame rf,
156  const Eigen::MatrixBase<Matrix6Like> & dJ);
157 
158 } // namespace pinocchio
159 
160 /* --- Details -------------------------------------------------------------------- */
161 /* --- Details -------------------------------------------------------------------- */
162 /* --- Details -------------------------------------------------------------------- */
163 
164 #include "pinocchio/algorithm/jacobian.hxx"
165 
166 #endif // ifndef __pinocchio_jacobian_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
ReferenceFrame
List of Reference Frames supported by Pinocchio.
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame or i...
data
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
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...
void getJointJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &dJ)
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (r...
Main pinocchio namespace.
Definition: timings.cpp:30
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 computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex jointId, 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_DEPRECATED void jointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex jointId, const Eigen::MatrixBase< Matrix6Like > &J)
This function is now deprecated and has been renamed into computeJointJacobian. It will be removed in...
Definition: jacobian.hpp:107
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
JointCollectionTpl & model


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:03