Namespaces | Functions
jacobian.hpp File Reference
#include "pinocchio/multibody/fwd.hpp"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/data.hpp"
#include "pinocchio/algorithm/jacobian.hxx"
Include dependency graph for jacobian.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 pinocchio
 Main pinocchio namespace.
 

Functions

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6Like >
void pinocchio::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 the result in the input argument J. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6xpinocchio::computeJointJacobians (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
 Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame. The result is accessible through data.J. This function assumes that pinocchio::forwardKinematics has been called before. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6xpinocchio::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. The result is accessible through data.J. This function computes also the forwardKinematics of the model. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType >
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6xpinocchio::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 depends both on q and v. The result is accessible through data.dJ. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6Like >
void pinocchio::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 in the local frame (rf = LOCAL) of the joint. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6Like >
void pinocchio::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 (rf = WORLD) or in the local frame (rf = LOCAL) of the joint. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6Like >
PINOCCHIO_DEPRECATED void pinocchio::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 future releases of Pinocchio. More...
 


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:00