Main pinocchio namespace. More...
Namespaces | |
buildModels | |
Build simple models. | |
casadi | |
cholesky | |
Cholesky decompositions. | |
container | |
Specialized containers. | |
deprecated | |
deprecation | |
explog | |
fcl | |
fix | |
forceSet | |
Group force actions. | |
fusion | |
helper | |
impl | |
internal | |
lua | |
Lua parsing. | |
math | |
motionSet | |
Group motion actions. | |
python | |
quaternion | |
Quaternion operations. | |
regressor | |
robot_wrapper | |
romeo_wrapper | |
rpy | |
Roll-pitch-yaw operations. | |
serialization | |
shortcuts | |
srdf | |
SRDF parsing. | |
urdf | |
URDF parsing. | |
utils | |
visualize | |
Enumerations | |
enum | { MAX_JOINT_NV = 6 } |
enum | { SELF = 0 } |
enum | ArgumentPosition { ARG0 = 0, ARG1 = 1, ARG2 = 2, ARG3 = 3, ARG4 = 4 } |
Argument position. Used as template parameter to refer to an argument. More... | |
enum | AssignmentOperatorType { SETTO, ADDTO, RMTO } |
enum | FrameType { OP_FRAME = 0x1 << 0, JOINT = 0x1 << 1, FIXED_JOINT = 0x1 << 2, BODY = 0x1 << 3, SENSOR = 0x1 << 4 } |
Enum on the possible types of frames. More... | |
enum | GeometryType { VISUAL, COLLISION } |
enum | KinematicLevel { POSITION = 0, VELOCITY = 1, ACCELERATION = 2 } |
List of Kinematics Level supported by Pinocchio. More... | |
enum | ModelFileExtensionType { UNKNOWN = 0, URDF } |
Supported model file extensions. More... | |
enum | ReferenceFrame { WORLD = 0, LOCAL = 1, LOCAL_WORLD_ALIGNED = 2 } |
List of Reference Frames supported by Pinocchio. More... | |
Functions | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorPool , typename TangentVectorPool1 , typename TangentVectorPool2 , typename TangentVectorPool3 > | |
void | aba (const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &tau, const Eigen::MatrixBase< TangentVectorPool3 > &a) |
A parallel version of the Articulated Body algorithm. It computes the forward dynamics, aka the joint acceleration according to the current state of the system and the desired joint torque. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | aba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau) |
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ForceDerived > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | aba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const container::aligned_vector< ForceDerived > &fext) |
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model. More... | |
template<typename D > | |
void | addJointAndBody (Model &model, const JointModelBase< D > &jmodel, const Model::JointIndex parent_id, const SE3 &joint_placement, const std::string &name, const Inertia &Y) |
template<typename Vector3Like , typename Matrix3Like > | |
void | addSkew (const Eigen::MatrixBase< Vector3Like > &v, const Eigen::MatrixBase< Matrix3Like > &M) |
Add skew matrix represented by a 3d vector to a given matrix, i.e. add the antisymmetric matrix representation of the cross product operator ( ) More... | |
template<typename Scalar , typename Vector3 , typename Matrix3 > | |
void | alphaSkew (const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M) |
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( ) More... | |
template<typename Scalar , typename Vector3 > | |
Eigen::Matrix< typename Vector3::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3)::Options > | alphaSkew (const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v) |
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( ) More... | |
void | appendGeometryModel (GeometryModel &geom_model1, const GeometryModel &geom_model2) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | appendModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb, ModelTpl< Scalar, Options, JointCollectionTpl > &model) |
Append a child model into a parent model, after a specific frame given by its index. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
ModelTpl< Scalar, Options, JointCollectionTpl > | appendModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb) |
Append a child model into a parent model, after a specific frame given by its index. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | appendModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const GeometryModel &geomModelA, const GeometryModel &geomModelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb, ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geomModel) |
Append a child model into a parent model, after a specific frame given by its index. More... | |
void | appendSuffixToPaths (std::vector< std::string > &list_of_paths, const std::string &suffix) |
For a given vector of paths, add a suffix inplace to each path and return the vector inplace. More... | |
template<int axis> | |
char | axisLabel () |
Generate the label (X, Y or Z) of the axis relative to its index. More... | |
template<> | |
char | axisLabel< 0 > () |
template<> | |
char | axisLabel< 1 > () |
template<> | |
char | axisLabel< 2 > () |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | bias (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointBiasVisitor to get the joint bias as a dense motion. More... | |
template<typename MotionVelocity , typename MotionAcceleration , typename OutputType > | |
void | bodyRegressor (const MotionDense< MotionVelocity > &v, const MotionDense< MotionAcceleration > &a, const Eigen::MatrixBase< OutputType > ®ressor) |
Computes the regressor for the dynamic parameters of a single rigid body. More... | |
template<typename MotionVelocity , typename MotionAcceleration > | |
Eigen::Matrix< typename MotionVelocity::Scalar, 6, 10, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionVelocity::Vector3)::Options > | bodyRegressor (const MotionDense< MotionVelocity > &v, const MotionDense< MotionAcceleration > &a) |
Computes the regressor for the dynamic parameters of a single rigid body. More... | |
void | buildAllJointsModel (Model &model) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | buildReducedModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::vector< JointIndex > list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model) |
Build a reduced model from a given input model and a list of joint to lock. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
ModelTpl< Scalar, Options, JointCollectionTpl > | buildReducedModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration) |
Build a reduced model from a given input model and a list of joint to lock. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | buildReducedModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const GeometryModel &geom_model, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model, GeometryModel &reduced_geom_model) |
Build a reduced model and a rededuced geometry model from a given input model, a given input geometry model and a list of joint to lock. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename GeometryModelAllocator , typename ConfigVectorType > | |
void | buildReducedModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::vector< GeometryModel, GeometryModelAllocator > &list_of_geom_models, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model, std::vector< GeometryModel, GeometryModelAllocator > &list_of_reduced_geom_models) |
Build a reduced model and a rededuced geometry model from a given input model, a given input geometry model and a list of joint to lock. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename Matrix6Type > | |
void | calc_aba (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I) |
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
void | calc_first_order (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcFirstOrderVisitor to compute the joint data kinematics at order one. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename ConfigVectorType > | |
void | calc_zero_order (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< ConfigVectorType > &q) |
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcZeroOrderVisitor to compute the joint data kinematics at order zero. More... | |
template<typename NewScalar , typename Scalar > | |
NewScalar | cast (const Scalar &value) |
template<typename NewScalar , typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
CastType< NewScalar, JointModelTpl< Scalar, Options, JointCollectionTpl > >::type | cast_joint (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl<Scalar,...> to cast it into JointModelTpl<NewScalar,...> More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & | ccrba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal momenta according to the current joint configuration and velocity. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & | centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true) |
Computes the center of mass position of a given model according to a particular joint configuration. The result is accessible through data.com[0] for the full body com and data.com[i] for the subtree supported by joint i (expressed in the joint i frame). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & | centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const bool computeSubtreeComs=true) |
Computes the center of mass position and velocity of a given model according to a particular joint configuration and velocity. The result is accessible through data.com[0], data.vcom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & | centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const bool computeSubtreeComs=true) |
Computes the center of mass position, velocity and acceleration of a given model according to a particular joint configuration, velocity and acceleration. The result is accessible through data.com[0], data.vcom[0], data.acom[0] for the full body com position, velocity and acceleation. And data.com[i], data.vcom[i] and data.acom[i] for the subtree supported by joint i (expressed in the joint i frame). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & | centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, KinematicLevel kinematic_level, const bool computeSubtreeComs=true) |
Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data and the requested kinematic_level. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
PINOCCHIO_DEPRECATED void | centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, int kinematic_level, const bool computeSubtreeComs=true) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & | centerOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true) |
Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
bool | checkData (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data) |
ModelFileExtensionType | checkModelFileExtension (const std::string &filename) |
Extract the type of the given model file according to its extension. More... | |
bool | checkVersionAtLeast (unsigned int major_version, unsigned int minor_version, unsigned int patch_version) |
Checks if the current version of Pinocchio is at least the version provided by the input arguments. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 > | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau) |
The derivatives of the Articulated-Body algorithm. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 > | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext, const Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau) |
The derivatives of the Articulated-Body algorithm with external forces. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau) |
The derivatives of the Articulated-Body algorithm. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext) |
The derivatives of the Articulated-Body algorithm with external forces. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
void | computeAllTerms (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the same time to: More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
PINOCCHIO_DEPRECATED const DataTpl< Scalar, Options, JointCollectionTpl >::Force & | computeCentroidalDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center of mass. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
PINOCCHIO_DEPRECATED const DataTpl< Scalar, Options, JointCollectionTpl >::Force & | computeCentroidalDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and its time derivative expressed around the center of mass. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename Matrix6xLike0 , typename Matrix6xLike1 , typename Matrix6xLike2 , typename Matrix6xLike3 > | |
void | computeCentroidalDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Eigen::MatrixBase< Matrix6xLike0 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da) |
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuration vector, velocity and acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & | computeCentroidalMap (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the Centroidal Momentum Matrix,. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & | computeCentroidalMapTimeVariation (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the Centroidal Momentum Matrix time derivative. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & | computeCentroidalMomentum (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center of mass. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & | computeCentroidalMomentum (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center of mass. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & | computeCentroidalMomentumTimeVariation (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and its time derivative expressed around the center of mass. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & | computeCentroidalMomentumTimeVariation (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and its time derivative expressed around the center of mass. More... | |
bool | computeCollisions (const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
bool | computeCollisions (const int num_threads, const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool stopAtFirstCollision=false) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorPool , typename CollisionVectorResult > | |
void | computeCollisions (const int num_threads, GeometryPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< CollisionVectorResult > &res, const bool stopAtFirstCollision=false) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | computeCoriolisMatrix (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the Coriolis Matrix of the Lagrangian dynamics: | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | computeForwardKinematicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acceleration for any joint of the model. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6xLike > | |
void | computeFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J) |
Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6xLike > | |
void | computeFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const Eigen::MatrixBase< Matrix6xLike > &J) |
Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xReturnType > | |
void | computeFrameKinematicRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the frame given as input. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x | computeFrameKinematicRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the frame given as input. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | computeGeneralizedGravity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the generalized gravity contribution of the Lagrangian dynamics: | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename ReturnMatrixType > | |
void | computeGeneralizedGravityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< ReturnMatrixType > &gravity_partial_dq) |
Computes the partial derivative of the generalized gravity contribution with respect to the joint configuration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6Like > | |
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 the result in the input argument J. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
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. 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> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & | 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 , typename TangentVectorType > | |
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 depends both on q and v. The result is accessible through data.dJ. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | computeJointKinematicHessians (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes all the terms required to compute the second order derivatives of the placement information, also know as the kinematic Hessian. This function assumes that the joint Jacobians (a.k.a data.J) has been computed first. See computeJointJacobians for such a function. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | computeJointKinematicHessians (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes all the terms required to compute the second order derivatives of the placement information, also know as the kinematic Hessian. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xReturnType > | |
void | computeJointKinematicRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame rf, const SE3Tpl< Scalar, Options > &placement, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor) |
Computes the kinematic regressor that links the joint placements variations of the whole kinematic tree to the placement variation of the frame rigidly attached to the joint and given by its placement w.r.t. to the joint frame. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x | computeJointKinematicRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame rf, const SE3Tpl< Scalar, Options > &placement) |
Computes the kinematic regressor that links the joint placements variations of the whole kinematic tree to the placement variation of the frame rigidly attached to the joint and given by its placement w.r.t. to the joint frame. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xReturnType > | |
void | computeJointKinematicRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the joint given as input. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x | computeJointKinematicRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame rf) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the joint given as input. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | computeJointTorqueRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Computes the joint torque regressor that links the joint torque to the dynamic parameters of each link according to the current the robot motion. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Scalar | computeKineticEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
Scalar | computeKineticEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename ConstraintMatrixType , typename KKTMatrixType > | |
void | computeKKTContactDynamicMatrixInverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Eigen::MatrixBase< KKTMatrixType > &KKTMatrix_inv, const Scalar &inv_damping=0.) |
Computes the inverse of the KKT matrix for dynamics with contact constraints. It computes the following matrix: | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & | computeMinverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the inverse of the joint space inertia matrix using Articulated Body formulation. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Scalar | computePotentialEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field. The result is accessible through data.potential_energy. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
Scalar | computePotentialEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field. The result is accessible through data.potential_energy. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 > | |
void | computeRNEADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da) |
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 > | |
void | computeRNEADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da) |
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | computeRNEADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | computeRNEADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext) |
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename Tensor1 , typename Tensor2 , typename Tensor3 , typename Tensor4 > | |
void | ComputeRNEASecondOrderDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Tensor1 &d2tau_dqdq, const Tensor2 &d2tau_dvdv, const Tensor3 &dtau_dqdv, const Tensor4 &dtau_dadq) |
Computes the Second-Order partial derivatives of the Recursive Newton Euler Algorithm w.r.t the joint configuration, the joint velocity and the joint acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | ComputeRNEASecondOrderDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Computes the Second-Order partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & | computeStaticRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the static regressor that links the center of mass positions of all the links to the center of mass of the complete model according to the current configuration of the robot. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | computeStaticTorque (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext) |
Computes the generalized static torque contribution of the Lagrangian dynamics: | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename ReturnMatrixType > | |
void | computeStaticTorqueDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options > > &fext, const Eigen::MatrixBase< ReturnMatrixType > &static_torque_partial_dq) |
Computes the partial derivative of the generalized gravity and external forces contributions (a.k.a static torque vector) with respect to the joint configuration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | computeSubtreeMasses (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Compute the mass of each kinematic subtree and store it in data.mass. The element mass[0] corresponds to the total mass of the model. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
ForceTpl< Scalar, Options > | computeSupportedForceByFrame (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id) |
Computes the force supported by a specific frame (given by frame_id) expressed in the LOCAL frame. The supported force corresponds to the sum of all the forces experienced after the given frame, i.e : More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
InertiaTpl< Scalar, Options > | computeSupportedInertiaByFrame (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, bool with_subtree) |
Compute the inertia supported by a specific frame (given by frame_id) expressed in the LOCAL frame. The total supported inertia corresponds to the sum of all the inertia after the given frame, i.e : More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Scalar | computeTotalMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model) |
Compute the total mass of the model and return it. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Scalar | computeTotalMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Compute the total mass of the model, put it in data.mass[0] and return it. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
ConstraintTpl< Eigen::Dynamic, Scalar, Options > | constraint_xd (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataVariant through JointConstraintVisitor to get the joint constraint as a dense constraint. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | copy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &origin, DataTpl< Scalar, Options, JointCollectionTpl > &dest, KinematicLevel kinematic_level) |
Copy part of the data from origin to dest . Template parameter can be used to select at which differential level the copy should occur. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
PINOCCHIO_DEPRECATED void | copy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &origin, DataTpl< Scalar, Options, JointCollectionTpl > &dest, int kinematic_level) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | crba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid Body Algorithm (Chapter 6, Rigid-Body Dynamics Algorithms, R. Featherstone, 2008). The result is accessible through data.M. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | crbaMinimal (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid Body Algorithm (Chapter 6, Rigid-Body Dynamics Algorithms, R. Featherstone, 2008). The result is accessible through data.M. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
JointDataTpl< Scalar, Options, JointCollectionTpl > | createData (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl. More... | |
template<typename Vector3 , typename Matrix3xIn , typename Matrix3xOut > | |
void | cross (const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout) |
Applies the cross product onto the columns of M. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & | dccrba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the time derivative of the Centroidal Momentum Matrix according to the current configuration and velocity vectors. More... | |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t , class JacobianOut_t > | |
void | dDifference (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg) |
template<ArgumentPosition arg, typename LieGroupCollection , class ConfigL_t , class ConfigR_t , class JacobianIn_t , class JacobianOut_t > | |
void | dDifference (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout) |
template<ArgumentPosition arg, typename LieGroupCollection , class ConfigL_t , class ConfigR_t , class JacobianIn_t , class JacobianOut_t > | |
void | dDifference (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t , class Tangent_t > | |
void | difference (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &v) |
template<typename LieGroupCollection , class Config_t , class Tangent_t , class JacobianOut_t > | |
void | dIntegrate (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) |
template<typename LieGroupCollection , class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
void | dIntegrate (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &J_in, int self, const Eigen::MatrixBase< JacobianOut_t > &J_out, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) |
template<typename LieGroupCollection , class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
void | dIntegrate (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, int self, const Eigen::MatrixBase< JacobianIn_t > &J_in, const Eigen::MatrixBase< JacobianOut_t > &J_out, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) |
template<typename LieGroupCollection , class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
void | dIntegrateTransport (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &J_in, const Eigen::MatrixBase< JacobianOut_t > &J_out, const ArgumentPosition arg) |
template<typename LieGroupCollection , class Config_t , class Tangent_t , class JacobianOut_t > | |
void | dIntegrateTransport (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > | dinv_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointDInvInertiaVisitor to get the D^{-1} matrix of the inertia matrix decomposition. More... | |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t > | |
ConfigL_t::Scalar | distance (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | emptyForwardPassBinaryVisit (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | emptyForwardPassBinaryVisitNoData (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | emptyForwardPassUnaryVisit (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | emptyForwardPassUnaryVisitNoData (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
template<typename Vector3Like > | |
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | exp3 (const Eigen::MatrixBase< Vector3Like > &v) |
Exp: so3 -> SO3. More... | |
template<typename MotionDerived > | |
SE3Tpl< typename MotionDerived::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options > | exp6 (const MotionDense< MotionDerived > &nu) |
Exp: se3 -> SE3. More... | |
template<typename Vector6Like > | |
SE3Tpl< typename Vector6Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options > | exp6 (const Eigen::MatrixBase< Vector6Like > &v) |
Exp: se3 -> SE3. More... | |
void | extractPathFromEnvVar (const std::string &env_var_name, std::vector< std::string > &list_of_paths, const std::string &delimiter=":") |
Parse an environment variable if exists and extract paths according to the delimiter. More... | |
std::vector< std::string > | extractPathFromEnvVar (const std::string &env_var_name, const std::string &delimiter=":") |
Parse an environment variable if exists and extract paths according to the delimiter. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ConstraintMatrixType , typename DriftVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | forwardDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Eigen::MatrixBase< DriftVectorType > &gamma, const Scalar inv_damping=0.) |
Compute the forward dynamics with contact constraints. Internally, pinocchio::computeAllTerms is called. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename TangentVectorType , typename ConstraintMatrixType , typename DriftVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | forwardDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< TangentVectorType > &tau, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Eigen::MatrixBase< DriftVectorType > &gamma, const Scalar inv_damping=0.) |
Compute the forward dynamics with contact constraints, assuming pinocchio::computeAllTerms has been called. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ConstraintMatrixType , typename DriftVectorType > | |
PINOCCHIO_DEPRECATED const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | forwardDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Eigen::MatrixBase< DriftVectorType > &gamma, const Scalar inv_damping, const bool updateKinematics) |
Compute the forward dynamics with contact constraints. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | forwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Update the joint placements according to the current joint configuration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
void | forwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Update the joint placements and spatial velocities according to the current joint configuration and velocity. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
void | forwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
Update the joint placements, spatial velocities and spatial accelerations according to the current joint configuration, velocity and acceleration. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & | frameBodyRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, FrameIndex frameId) |
Computes the regressor for the dynamic parameters of a rigid body attached to a given frame, puts the result in data.bodyRegressor and returns it. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6xLike > | |
PINOCCHIO_DEPRECATED void | frameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const FrameIndex frameId, const Eigen::MatrixBase< Matrix6xLike > &J) |
This function is now deprecated and has been renamed computeFrameJacobian. This signature will be removed in future release of Pinocchio. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | framesForwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
First calls the forwardKinematics on the model, then computes the placement of each frame. /sa pinocchio::forwardKinematics. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
PINOCCHIO_DEPRECATED void | framesForwardKinematics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Updates the position of each frame contained in the model. This function is now deprecated and has been renamed updateFramePlacements. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | getAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL) |
Returns the spatial acceleration of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xOut > | |
void | getCenterOfMassVelocityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix3xOut > &vcom_partial_dq) |
Computes the partial derivatie of the center-of-mass velocity with respect to the joint configuration q. You must first call computeAllTerms(model,data,q,v) or computeCenterOfMass(model,data,q,v) before calling this function. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xLike0 , typename Matrix6xLike1 , typename Matrix6xLike2 , typename Matrix6xLike3 > | |
void | getCentroidalDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Matrix6xLike1 > &dh_dq, const Eigen::MatrixBase< Matrix6xLike1 > &dhdot_dq, const Eigen::MatrixBase< Matrix6xLike2 > &dhdot_dv, const Eigen::MatrixBase< Matrix6xLike3 > &dhdot_da) |
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives. pinocchio::computeRNEADerivatives should have been called first. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | getClassicalAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL) |
Returns the "classical" acceleration of the joint expressed in the desired reference frame. This is different from the "spatial" acceleration in that centrifugal effects are accounted for. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & | getComFromCrba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Extracts the center of mass position from the joint space inertia matrix (also called the mass matrix). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | getCoriolisMatrix (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Retrives the Coriolis Matrix of the Lagrangian dynamics: | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | getFrameAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL) |
Returns the spatial acceleration of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 > | |
void | getFrameAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_da) |
Computes the partial derivatives of the frame acceleration quantity with respect to q, v and a. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 , typename Matrix6xOut5 > | |
void | getFrameAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut5 > &a_partial_da) |
Computes the partial derivatives of the frame acceleration quantity with respect to q, v and a. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | getFrameClassicalAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL) |
Returns the "classical" acceleration of the Frame expressed in the desired reference frame. This is different from the "spatial" acceleration in that centrifugal effects are accounted for. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xLike > | |
void | getFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &J) |
Returns the jacobian of the frame expressed either expressed in the LOCAL frame coordinate system or in the WORLD coordinate system, depending on the value of rf. You must first call pinocchio::computeJointJacobians followed by pinocchio::framesForwardKinematics to update placement values in data structure. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xLike > | |
void | getFrameJacobianTimeVariation (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &dJ) |
Computes the Jacobian time variation of a specific frame (given by frame_id) expressed either in the LOCAL frame. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | getFrameVelocity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL) |
Returns the spatial velocity of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 > | |
void | getFrameVelocityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv) |
Computes the partial derivatives of the frame velocity quantity with respect to q and v. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & | getJacobianComFromCrba (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Extracts both the jacobian of the center of mass (CoM), the total mass of the system and the CoM position from the joint space inertia matrix (also called the mass matrix). The results are accessible through data.Jcom, data.mass[0] and data.com[0] and are both expressed in the world frame. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xLike > | |
void | getJacobianSubtreeCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex &rootSubtreeId, const Eigen::MatrixBase< Matrix3xLike > &res) |
Retrieves the Jacobian of the center of mass of the given subtree according to the current value stored in data. It assumes that pinocchio::jacobianCenterOfMass has been called first with computeSubtreeComs equals to true. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 > | |
void | getJointAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_da) |
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint configuration, velocity and acceleration. You must first call computForwardKinematicsDerivatives before calling this function. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 , typename Matrix6xOut5 > | |
void | getJointAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut5 > &a_partial_da) |
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint configuration, velocity and acceleration. You must first call computForwardKinematicsDerivatives before calling this function. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6Like > | |
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 in the local frame (rf = LOCAL) of the joint. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6Like > | |
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 (rf = WORLD) or in the local frame (rf = LOCAL) of the joint. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | getJointKinematicHessian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const ReferenceFrame rf, Tensor< Scalar, 3, Options > &kinematic_hessian) |
Retrieves the kinematic Hessian of a given joint according to the values aleardy computed by computeJointKinematicHessians and stored in data. While the kinematic Jacobian of a given joint frame corresponds to the first order derivative of the placement variation with respect to , the kinematic Hessian corresponds to the second order derivation of placement variation, which in turns also corresponds to the first order derivative of the kinematic Jacobian. The frame in which the kinematic Hessian is precised by the input argument rf. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Tensor< Scalar, 3, Options > | getJointKinematicHessian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const ReferenceFrame rf) |
Retrieves the kinematic Hessian of a given joint according to the values aleardy computed by computeJointKinematicHessians and stored in data. While the kinematic Jacobian of a given joint frame corresponds to the first order derivative of the placement variation with respect to , the kinematic Hessian corresponds to the second order derivation of placement variation, which in turns also corresponds to the first order derivative of the kinematic Jacobian. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 > | |
void | getJointVelocityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv) |
Computes the partial derivaties of the spatial velocity of a given with respect to the joint configuration and velocity. You must first call computForwardKinematicsDerivatives before calling this function. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConstraintMatrixType , typename KKTMatrixType > | |
void | getKKTContactDynamicMatrixInverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Eigen::MatrixBase< KKTMatrixType > &KKTMatrix_inv) |
Computes the inverse of the KKT matrix for dynamics with contact constraints. It computes the following matrix: | |
int | getOpenMPNumThreadsEnv () |
Returns the number of thread defined by the environment variable OMP_NUM_THREADS. If this variable is not defined, this simply returns the default value 1. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | getVelocity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL) |
Returns the spatial velocity of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
const std::vector< bool > | hasConfigurationLimit (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointConfigurationLimitVisitor to get the configurations limits. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
const std::vector< bool > | hasConfigurationLimitInTangent (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limits in tangent space. More... | |
template<typename Derived > | |
bool | hasNaN (const Eigen::DenseBase< Derived > &m) |
template<typename NewScalar , typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointModelDerived > | |
bool | hasSameIndexes (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel) |
Check whether JointModelTpl<Scalar,...> has the indexes than another JointModelDerived. More... | |
template<typename Scalar , typename Vector3Like1 , typename Vector3Like2 , typename Matrix3Like > | |
void | Hlog3 (const Scalar &theta, const Eigen::MatrixBase< Vector3Like1 > &log, const Eigen::MatrixBase< Vector3Like2 > &v, const Eigen::MatrixBase< Matrix3Like > &vt_Hlog) |
template<typename Matrix3Like1 , typename Vector3Like , typename Matrix3Like2 > | |
void | Hlog3 (const Eigen::MatrixBase< Matrix3Like1 > &R, const Eigen::MatrixBase< Vector3Like > &v, const Eigen::MatrixBase< Matrix3Like2 > &vt_Hlog) |
Second order derivative of log3. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
JointIndex | id (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
int | idx_q (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space corresponding to the first degree of freedom of the Joint. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
int | idx_v (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corresponding to the first joint tangent space degree. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename ConstraintMatrixType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | impulseDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v_before, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Scalar r_coeff=0., const Scalar inv_damping=0.) |
Compute the impulse dynamics with contact constraints. Internally, pinocchio::crba is called. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename ConstraintMatrixType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | impulseDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< TangentVectorType > &v_before, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Scalar r_coeff=0., const Scalar inv_damping=0.) |
Compute the impulse dynamics with contact constraints, assuming pinocchio::crba has been called. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename ConstraintMatrixType > | |
PINOCCHIO_DEPRECATED const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | impulseDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v_before, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Scalar r_coeff, const bool updateKinematics) |
Compute the impulse dynamics with contact constraints. More... | |
template<typename LieGroupCollection , class ConfigIn_t , class Tangent_t , class ConfigOut_t > | |
void | integrate (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout) |
Visit a LieGroupVariant to call its integrate method. More... | |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t , class ConfigOut_t > | |
void | interpolate (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const typename ConfigL_t::Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) |
template<typename MatrixIn , typename MatrixOut > | |
void | inverse (const Eigen::MatrixBase< MatrixIn > &m_in, const Eigen::MatrixBase< MatrixOut > &dest) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointModelDerived > | |
bool | isEqual (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel) |
Visit a JointModelTpl<Scalar,...> to compare it to JointModelDerived. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointDataDerived > | |
bool | isEqual (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointDataBase< JointDataDerived > &jmodel) |
Visit a JointDataTpl<Scalar,...> to compare it to another JointData. More... | |
template<typename LieGroupCollection , class Config_t > | |
bool | isNormalized (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &qin, const typename Config_t::Scalar &prec=Eigen::NumTraits< typename Config_t::Scalar >::dummy_precision()) |
template<typename VectorLike > | |
bool | isNormalized (const Eigen::MatrixBase< VectorLike > &vec, const typename VectorLike::RealScalar &prec=Eigen::NumTraits< typename VectorLike::Scalar >::dummy_precision()) |
Check whether the input vector is Normalized within the given precision. More... | |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t > | |
bool | isSameConfiguration (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const typename ConfigL_t::Scalar &prec) |
template<typename MatrixLike > | |
bool | isUnitary (const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision()) |
Check whether the input matrix is Unitary within the given precision. More... | |
template<typename MatrixLike > | |
bool | isZero (const Eigen::MatrixBase< MatrixLike > &m, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision()) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & | jacobianCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true) |
Computes both the jacobian and the the center of mass position of a given model according to a particular joint configuration. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & | jacobianCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true) |
Computes both the jacobian and the the center of mass position of a given model according to the current value stored in data. It assumes that forwardKinematics has been called first. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix3xLike > | |
void | jacobianSubtreeCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex &rootSubtreeId, const Eigen::MatrixBase< Matrix3xLike > &res) |
Computes the Jacobian of the center of mass of the given subtree according to a particular joint configuration. In addition, the algorithm also computes the Jacobian of all the joints (. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xLike > | |
void | jacobianSubtreeCenterOfMass (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex &rootSubtreeId, const Eigen::MatrixBase< Matrix3xLike > &res) |
Computes the Jacobian of the center of mass of the given subtree according to the current value stored in data. It assumes that forwardKinematics has been called first. More... | |
template<AssignmentOperatorType op, typename Vector3Like , typename Matrix3Like > | |
void | Jexp3 (const Eigen::MatrixBase< Vector3Like > &r, const Eigen::MatrixBase< Matrix3Like > &Jexp) |
Derivative of
. More... | |
template<typename Vector3Like , typename Matrix3Like > | |
void | Jexp3 (const Eigen::MatrixBase< Vector3Like > &r, const Eigen::MatrixBase< Matrix3Like > &Jexp) |
Derivative of
. More... | |
template<AssignmentOperatorType op, typename MotionDerived , typename Matrix6Like > | |
void | Jexp6 (const MotionDense< MotionDerived > &nu, const Eigen::MatrixBase< Matrix6Like > &Jexp) |
Derivative of exp6 Computed as the inverse of Jlog6. More... | |
template<typename MotionDerived , typename Matrix6Like > | |
void | Jexp6 (const MotionDense< MotionDerived > &nu, const Eigen::MatrixBase< Matrix6Like > &Jexp) |
Derivative of exp6 Computed as the inverse of Jlog6. More... | |
template<typename Scalar , typename Vector3Like , typename Matrix3Like > | |
void | Jlog3 (const Scalar &theta, const Eigen::MatrixBase< Vector3Like > &log, const Eigen::MatrixBase< Matrix3Like > &Jlog) |
Derivative of log3. More... | |
template<typename Matrix3Like1 , typename Matrix3Like2 > | |
void | Jlog3 (const Eigen::MatrixBase< Matrix3Like1 > &R, const Eigen::MatrixBase< Matrix3Like2 > &Jlog) |
Derivative of log3. More... | |
template<typename Scalar , int Options, typename Matrix6Like > | |
void | Jlog6 (const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog) |
Derivative of log6. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
SE3Tpl< Scalar, Options > | joint_transform (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointTransformVisitor to get the joint internal transform (transform between the entry frame and the exit frame of the joint). More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & | jointBodyRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, JointIndex jointId) |
Computes the regressor for the dynamic parameters of a rigid body attached to a given joint, puts the result in data.bodyRegressor and returns it. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename Matrix6Like > | |
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 future releases of Pinocchio. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
PINOCCHIO_DEPRECATED Scalar | kineticEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const bool update_kinematics) |
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy. More... | |
template<typename Matrix3Like > | |
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | log3 (const Eigen::MatrixBase< Matrix3Like > &R, typename Matrix3Like::Scalar &theta) |
Same as log3. More... | |
template<typename Matrix3Like > | |
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | log3 (const Eigen::MatrixBase< Matrix3Like > &R) |
Log: SO(3)-> so(3). More... | |
template<typename Scalar , int Options> | |
MotionTpl< Scalar, Options > | log6 (const SE3Tpl< Scalar, Options > &M) |
Log: SE3 -> se3. More... | |
template<typename Matrix4Like > | |
MotionTpl< typename Matrix4Like::Scalar, Eigen::internal::traits< Matrix4Like >::Options > | log6 (const Eigen::MatrixBase< Matrix4Like > &M) |
Log: SE3 -> se3. More... | |
AlgorithmCheckerList< ParentChecker, CRBAChecker, ABAChecker > | makeDefaultCheckerList () |
Default checker-list, used as the default argument in Model::check(). More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
MotionTpl< Scalar, Options > | motion (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointMotionVisitor to get the joint internal motion as a dense motion. More... | |
template<typename LieGroupCollection > | |
std::string | name (const LieGroupGenericTpl< LieGroupCollection > &lg) |
Visit a LieGroupVariant to get the name of it. More... | |
template<typename LieGroupCollection > | |
Eigen::Matrix< typename LieGroupCollection::Scalar, Eigen::Dynamic, 1, LieGroupCollection::Options > | neutral (const LieGroupGenericTpl< LieGroupCollection > &lg) |
Visit a LieGroupVariant to get the neutral element of it. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | nonLinearEffects (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects), also called the bias terms of the Lagrangian dynamics: | |
template<typename LieGroupCollection , class Config_t > | |
void | normalize (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &qout) |
template<typename Matrix3 > | |
void | normalizeRotation (const Eigen::MatrixBase< Matrix3 > &rot) |
Orthogonormalization procedure for a rotation matrix (closed enough to SO(3)). More... | |
template<typename LieGroupCollection > | |
int | nq (const LieGroupGenericTpl< LieGroupCollection > &lg) |
Visit a LieGroupVariant to get the dimension of the Lie group configuration space. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
int | nq (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space. More... | |
template<typename LieGroupCollection > | |
int | nv (const LieGroupGenericTpl< LieGroupCollection > &lg) |
Visit a LieGroupVariant to get the dimension of the Lie group tangent space. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
int | nv (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointDataDerived > | |
bool | operator!= (const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointModelDerived > | |
bool | operator!= (const JointModelBase< JointModelDerived > &joint_model, const JointModelTpl< Scalar, Options, JointCollectionTpl > &joint_model_generic) |
template<typename Scalar , int Options, typename Vector6Like > | |
MotionRef< const Vector6Like > | operator* (const ConstraintIdentityTpl< Scalar, Options > &, const Eigen::MatrixBase< Vector6Like > &v) |
template<typename Scalar , int Options, typename ConstraintDerived > | |
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType | operator* (const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint) |
 . More... | |
template<typename S1 , int O1, typename S2 , int O2> | |
InertiaTpl< S1, O1 >::Matrix6 | operator* (const InertiaTpl< S1, O1 > &Y, const ConstraintIdentityTpl< S2, O2 > &) |
template<typename MotionDerived > | |
internal::RHSScalarMultiplication< MotionDerived, typename MotionDerived::Scalar >::ReturnType | operator* (const typename MotionDerived::Scalar &alpha, const MotionBase< MotionDerived > &motion) |
template<typename MatrixDerived , typename ConstraintDerived > | |
MultiplicationOp< Eigen::MatrixBase< MatrixDerived >, ConstraintDerived >::ReturnType | operator* (const Eigen::MatrixBase< MatrixDerived > &Y, const ConstraintBase< ConstraintDerived > &constraint) |
 . More... | |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S1, 6, 3, O1 > | operator* (const InertiaTpl< S1, O1 > &Y, const ConstraintSphericalZYXTpl< S2, O2 > &S) |
template<typename F1 > | |
traits< F1 >::ForcePlain | operator* (const typename traits< F1 >::Scalar alpha, const ForceDense< F1 > &f) |
Basic operations specialization. More... | |
template<typename Matrix6Like , typename S2 , int O2> | |
const MatrixMatrixProduct< typename Eigen::internal::remove_const< typename SizeDepType< 3 >::ColsReturn< Matrix6Like >::ConstType >::type, typename ConstraintSphericalZYXTpl< S2, O2 >::Matrix3 >::type | operator* (const Eigen::MatrixBase< Matrix6Like > &Y, const ConstraintSphericalZYXTpl< S2, O2 > &S) |
template<typename M1 > | |
traits< M1 >::MotionPlain | operator* (const typename traits< M1 >::Scalar alpha, const MotionDense< M1 > &v) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S2, 6, 3, O2 > | operator* (const InertiaTpl< S1, O1 > &Y, const ConstraintSphericalTpl< S2, O2 > &) |
template<typename M6Like , typename S2 , int O2> | |
SizeDepType< 3 >::ColsReturn< M6Like >::ConstType | operator* (const Eigen::MatrixBase< M6Like > &Y, const ConstraintSphericalTpl< S2, O2 > &) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S1, 6, 3, O1 > | operator* (const InertiaTpl< S1, O1 > &Y, const ConstraintPlanarTpl< S2, O2 > &) |
template<typename M6Like , typename S2 , int O2> | |
Eigen::Matrix< S2, 6, 3, O2 > | operator* (const Eigen::MatrixBase< M6Like > &Y, const ConstraintPlanarTpl< S2, O2 > &) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S2, 6, 3, O2 > | operator* (const InertiaTpl< S1, O1 > &Y, const ConstraintTranslationTpl< S2, O2 > &) |
template<typename M6Like , typename S2 , int O2> | |
const SizeDepType< 3 >::ColsReturn< M6Like >::ConstType | operator* (const Eigen::MatrixBase< M6Like > &Y, const ConstraintTranslationTpl< S2, O2 > &) |
template<typename M1 , typename Scalar , int Options> | |
const M1 & | operator+ (const MotionBase< M1 > &v, const MotionZeroTpl< Scalar, Options > &) |
template<typename Scalar , int Options, typename M1 > | |
const M1 & | operator+ (const MotionZeroTpl< Scalar, Options > &, const MotionBase< M1 > &v) |
template<typename Scalar , int Options, int axis, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionPrismaticTpl< Scalar, Options, axis > &m1, const MotionDense< MotionDerived > &m2) |
template<typename Scalar , int Options, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionPrismaticUnalignedTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2) |
template<typename S1 , int O1, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionTranslationTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2) |
template<typename S1 , int O1, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionSphericalTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2) |
template<typename S1 , int O1, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionRevoluteUnalignedTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2) |
template<typename Scalar , int Options, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2) |
template<typename S1 , int O1, int axis, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionRevoluteTpl< S1, O1, axis > &m1, const MotionDense< MotionDerived > &m2) |
template<typename Derived > | |
std::ostream & | operator<< (std::ostream &os, const LieGroupBase< Derived > &lg) |
template<typename LieGroupCollection > | |
std::ostream & | operator<< (std::ostream &os, const LieGroupGenericTpl< LieGroupCollection > &lg) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
std::ostream & | operator<< (std::ostream &os, const JointDataCompositeTpl< Scalar, Options, JointCollectionTpl > &jdata) |
template<typename Scalar , int Options> | |
std::ostream & | operator<< (std::ostream &os, const FrameTpl< Scalar, Options > &f) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
std::ostream & | operator<< (std::ostream &os, const JointModelCompositeTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointDataDerived > | |
bool | operator== (const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointModelDerived > | |
bool | operator== (const JointModelBase< JointModelDerived > &joint_model, const JointModelTpl< Scalar, Options, JointCollectionTpl > &joint_model_generic) |
template<typename MotionDerived , typename S2 , int O2, int axis> | |
EIGEN_STRONG_INLINE MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionPrismaticTpl< S2, O2, axis > &m2) |
template<typename MotionDerived , typename S2 , int O2> | |
MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionPrismaticUnalignedTpl< S2, O2 > &m2) |
template<typename MotionDerived , typename S2 , int O2> | |
MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionRevoluteUnalignedTpl< S2, O2 > &m2) |
template<typename M1 , typename M2 > | |
traits< M1 >::MotionPlain | operator^ (const MotionDense< M1 > &v1, const MotionDense< M2 > &v2) |
Basic operations specialization. More... | |
template<typename M1 , typename F1 > | |
traits< F1 >::ForcePlain | operator^ (const MotionDense< M1 > &v, const ForceBase< F1 > &f) |
template<typename MotionDerived , typename S2 , int O2> | |
MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionSphericalTpl< S2, O2 > &m2) |
template<typename MotionDerived , typename S2 , int O2, int axis> | |
EIGEN_STRONG_INLINE MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionRevoluteTpl< S2, O2, axis > &m2) |
template<typename MotionDerived , typename S2 , int O2> | |
MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2) |
template<typename MotionDerived , typename S2 , int O2> | |
MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionTranslationTpl< S2, O2 > &m2) |
template<typename Scalar > | |
const Scalar | PI () |
Returns the value of PI according to the template parameters Scalar. More... | |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointData) JointDataVector |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector |
PINOCCHIO_DEFINE_ALGO_CHECKER (Parent) | |
Simple model checker, that assert that model.parents is indeed a tree. More... | |
PINOCCHIO_DEFINE_ALGO_CHECKER (CRBA) | |
PINOCCHIO_DEFINE_ALGO_CHECKER (ABA) | |
PINOCCHIO_DEFINE_COMPARISON_OP (equal_to_op,==) | |
PINOCCHIO_DEFINE_COMPARISON_OP (not_equal_to_op,!=) | |
PINOCCHIO_DEFINE_COMPARISON_OP (less_than_op,<) | |
PINOCCHIO_DEFINE_COMPARISON_OP (greater_than_op,>) | |
PINOCCHIO_DEFINE_COMPARISON_OP (less_than_or_equal_to_op,<=) | |
PINOCCHIO_DEFINE_COMPARISON_OP (greater_than_or_equal_to_op,>=) | |
template<typename Matrix3 > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix3) orthogonalProjection(const Eigen | |
Orthogonal projection of a matrix on the SO(3) manifold. More... | |
template<typename Vector3 , typename Matrix3x > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix3x) cross(const Eigen | |
Applies the cross product onto the columns of M. More... | |
template<typename Matrix6Like , typename S2 , int O2> | |
PINOCCHIO_EIGEN_REF_CONST_TYPE (Matrix6Like) operator*(const Eigen | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelRevoluteUnboundedUnalignedTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelFreeFlyerTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelSphericalZYXTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelSphericalTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelPlanarTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelTranslationTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelPrismaticUnalignedTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelRevoluteUnalignedTpl) | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
PINOCCHIO_DEPRECATED Scalar | potentialEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool update_kinematics) |
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field. The result is accessible through data.potential_energy. More... | |
std::string | printVersion (const std::string &delimiter=".") |
Returns the current version of Pinocchio as a string using the following standard: PINOCCHIO_MINOR_VERSION.PINOCCHIO_MINOR_VERSION.PINOCCHIO_PATCH_VERSION. More... | |
template<typename LieGroupCollection , class Config_t > | |
void | random (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &qout) |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t , class ConfigOut_t > | |
void | randomConfiguration (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< ConfigOut_t > &qout) |
std::string | randomStringGenerator (const int len) |
Generate a random string composed of alphanumeric symbols of a given length. More... | |
std::string | retrieveResourcePath (const std::string &string, const std::vector< std::string > &package_dirs) |
Retrieve the path of the file whose path is given in URL-format. Currently convert from the following patterns : package:// or file://. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | rnea (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system and the desired joint accelerations. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorPool , typename TangentVectorPool1 , typename TangentVectorPool2 , typename TangentVectorPool3 > | |
void | rnea (const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau) |
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system and the desired joint accelerations. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ForceDerived > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | rnea (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const container::aligned_vector< ForceDerived > &fext) |
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system, the desired joint accelerations and the external forces. More... | |
std::vector< std::string > | rosPaths () |
Parse the environment variables ROS_PACKAGE_PATH / AMENT_PREFIX_PATH and extract paths. More... | |
template<typename Vector3Like > | |
PINOCCHIO_DEPRECATED void | setGeometryMeshScales (GeometryModel &geom_model, const Eigen::MatrixBase< Vector3Like > &meshScale) |
Set a mesh scaling vector to each GeometryObject contained in the the GeometryModel. More... | |
PINOCCHIO_DEPRECATED void | setGeometryMeshScales (GeometryModel &geom_model, const double meshScale) |
Set an isotropic mesh scaling to each GeometryObject contained in the the GeometryModel. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
void | setIndexes (JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v) |
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic chain. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
std::string | shortname (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model. More... | |
template<typename Scalar > | |
Scalar | sign (const Scalar &t) |
Returns the robust sign of t. More... | |
template<typename S1 , typename S2 , typename S3 > | |
void | SINCOS (const S1 &a, S2 *sa, S3 *ca) |
Computes sin/cos values of a given input scalar. More... | |
template<typename Vector3 , typename Matrix3 > | |
void | skew (const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M) |
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation of the cross product operator ( ) More... | |
template<typename D > | |
Eigen::Matrix< typename D::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(D)::Options > | skew (const Eigen::MatrixBase< D > &v) |
Computes the skew representation of a given 3D vector, i.e. the antisymmetric matrix representation of the cross product operator. More... | |
template<typename V1 , typename V2 , typename Matrix3 > | |
void | skewSquare (const Eigen::MatrixBase< V1 > &u, const Eigen::MatrixBase< V2 > &v, const Eigen::MatrixBase< Matrix3 > &C) |
Computes the square cross product linear operator C(u,v) such that for any vector w, . More... | |
template<typename V1 , typename V2 > | |
Eigen::Matrix< typename V1::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(V1)::Options > | skewSquare (const Eigen::MatrixBase< V1 > &u, const Eigen::MatrixBase< V2 > &v) |
Computes the square cross product linear operator C(u,v) such that for any vector w, . More... | |
template<typename LieGroupCollection , class ConfigL_t , class ConfigR_t > | |
ConfigL_t::Scalar | squaredDistance (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) |
hpp::fcl::Transform3f | toFclTransform3f (const SE3 &m) |
SE3 | toPinocchioSE3 (const hpp::fcl::Transform3f &tf) |
template<typename Vector3 , typename Scalar , typename Matrix3 > | |
void | toRotationMatrix (const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res) |
Computes a rotation matrix from a vector and values of sin and cos orientations values. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | u_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointUInertiaVisitor to get the U matrix of the inertia matrix decomposition. More... | |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | udinv_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointUDInvInertiaVisitor to get U*D^{-1} matrix of the inertia matrix decomposition. More... | |
template<typename Matrix3 , typename Vector3 > | |
void | unSkew (const Eigen::MatrixBase< Matrix3 > &M, const Eigen::MatrixBase< Vector3 > &v) |
Inverse of skew operator. From a given skew-symmetric matrix M of dimension 3x3, it extracts the supporting vector, i.e. the entries of M. Mathematically speacking, it computes such that . More... | |
template<typename Matrix3 > | |
Eigen::Matrix< typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3)::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3)::Options > | unSkew (const Eigen::MatrixBase< Matrix3 > &M) |
Inverse of skew operator. From a given skew-symmetric matrix M of dimension 3x3, it extracts the supporting vector, i.e. the entries of M. Mathematically speacking, it computes such that . More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::SE3 & | updateFramePlacement (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id) |
Updates the placement of the given frame. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | updateFramePlacements (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Updates the position of each frame contained in the model. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | updateGeometryPlacements (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q) |
Apply a forward kinematics and update the placement of the geometry objects. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | updateGeometryPlacements (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data) |
Update the placement of the geometry objects according to the current joint placements contained in data. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | updateGlobalPlacements (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Update the global placement of the joints oMi according to the relative placements of the joints. More... | |
API with return value as argument | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename ReturnType > | |
void | integrate (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout) |
Integrate a configuration vector for the specified model for a tangent vector during one unit time. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename ReturnType > | |
void | integrate (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout) |
Integrate a configuration vector for the specified model for a tangent vector during one unit time. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | interpolate (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1, const Scalar &u, const Eigen::MatrixBase< ReturnType > &qout) |
Interpolate two configurations for a given model. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | difference (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1, const Eigen::MatrixBase< ReturnType > &dvout) |
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | difference (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1, const Eigen::MatrixBase< ReturnType > &dvout) |
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | squaredDistance (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1, const Eigen::MatrixBase< ReturnType > &out) |
Squared distance between two configuration vectors. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | squaredDistance (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1, const Eigen::MatrixBase< ReturnType > &out) |
Squared distance between two configuration vectors. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | randomConfiguration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout) |
Generate a configuration vector uniformly sampled among provided limits. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 , typename ReturnType > | |
void | randomConfiguration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout) |
Generate a configuration vector uniformly sampled among provided limits. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ReturnType > | |
void | neutral (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout) |
Return the neutral configuration element related to the model configuration space. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ReturnType > | |
void | neutral (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout) |
Return the neutral configuration element related to the model configuration space. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType > | |
void | dIntegrate (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType > &J, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into the tangent space at identity. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType > | |
void | dIntegrate (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType > &J, const ArgumentPosition arg) |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into the tangent space at identity. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType > | |
void | dIntegrate (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType > &J, const ArgumentPosition arg, const AssignmentOperatorType op) |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into the tangent space at identity. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType1 , typename JacobianMatrixType2 > | |
void | dIntegrateTransport (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType1 > &Jin, const Eigen::MatrixBase< JacobianMatrixType2 > &Jout, const ArgumentPosition arg) |
Transport a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType1 , typename JacobianMatrixType2 > | |
void | dIntegrateTransport (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType1 > &Jin, const Eigen::MatrixBase< JacobianMatrixType2 > &Jout, const ArgumentPosition arg) |
Transport a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType > | |
void | dIntegrateTransport (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType > &J, const ArgumentPosition arg) |
Transport in place a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType , typename JacobianMatrixType > | |
void | dIntegrateTransport (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< JacobianMatrixType > &J, const ArgumentPosition arg) |
Transport in place a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVector1 , typename ConfigVector2 , typename JacobianMatrix > | |
void | dDifference (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVector1 > &q0, const Eigen::MatrixBase< ConfigVector2 > &q1, const Eigen::MatrixBase< JacobianMatrix > &J, const ArgumentPosition arg) |
Computes the Jacobian of a small variation of the configuration vector into the tangent space at identity. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVector1 , typename ConfigVector2 , typename JacobianMatrix > | |
void | dDifference (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVector1 > &q0, const Eigen::MatrixBase< ConfigVector2 > &q1, const Eigen::MatrixBase< JacobianMatrix > &J, const ArgumentPosition arg) |
Computes the Jacobian of a small variation of the configuration vector into the tangent space at identity. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
Scalar | squaredDistanceSum (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1) |
Overall squared distance between two configuration vectors. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
Scalar | squaredDistanceSum (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1) |
Overall squared distance between two configuration vectors, namely . More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
Scalar | distance (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1) |
Distance between two configuration vectors, namely . More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
Scalar | distance (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1) |
Distance between two configuration vectors. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | normalize (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout) |
Normalize a configuration vector. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | normalize (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout) |
Normalize a configuration vector. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
bool | isNormalized (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) |
Check whether a configuration vector is normalized within the given precision provided by prec. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
bool | isNormalized (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) |
Check whether a configuration vector is normalized within the given precision provided by prec. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
bool | isSameConfiguration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q1, const Eigen::MatrixBase< ConfigVectorIn2 > &q2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) |
Return true if the given configurations are equivalents, within the given precision. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
bool | isSameConfiguration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q1, const Eigen::MatrixBase< ConfigVectorIn2 > &q2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) |
Return true if the given configurations are equivalents, within the given precision. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVector , typename JacobianMatrix > | |
void | integrateCoeffWiseJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVector > &q, const Eigen::MatrixBase< JacobianMatrix > &jacobian) |
Return the Jacobian of the integrate function for the components of the config vector. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVector , typename JacobianMatrix > | |
void | integrateCoeffWiseJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVector > &q, const Eigen::MatrixBase< JacobianMatrix > &jacobian) |
Return the Jacobian of the integrate function for the components of the config vector. More... | |
Variables | |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef BiasZeroTpl< double, 0 > | BiasZero |
template<typename Scalar , int Options = 0> | |
struct PINOCCHIO_DEPRECATED | BiasZeroTpl |
submodules = inspect.getmembers(pinocchio_pywrap, inspect.ismodule) | |
bool | WITH_HPP_FCL_BINDINGS = True |
API that allocates memory | |
Options | |
JointCollectionTpl & | model |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & | q |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & | v |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & | q0 |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & | q1 |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > const Scalar & | u |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & | lowerLimits |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & | upperLimits |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (ConfigVectorType) integrate(const ModelTpl< Scalar | |
Integrate a configuration vector for the specified model for a tangent vector during one unit time. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (ConfigVectorType) integrate(const ModelTpl< Scalar | |
Integrate a configuration vector for the specified model for a tangent vector during one unit time. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (ConfigVectorIn1) interpolate(const ModelTpl< Scalar | |
Interpolate two configurations for a given model. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (ConfigVectorIn1) difference(const ModelTpl< Scalar | |
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS ((typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType)) randomConfiguration(const ModelTpl< Scalar | |
Generate a configuration vector uniformly sampled among given limits. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorIn1 , typename ConfigVectorIn2 > | |
PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS ((typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType)) randomConfiguration(const ModelTpl< Scalar | |
Generate a configuration vector uniformly sampled among provided limits. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS ((typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType)) randomConfiguration(const ModelTpl< Scalar | |
Generate a configuration vector uniformly sampled among the joint limits of the specified Model. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS ((typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType)) randomConfiguration(const ModelTpl< Scalar | |
Generate a configuration vector uniformly sampled among the joint limits of the specified Model. More... | |
template<typename LieGroup_t , typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > | neutral (const ModelTpl< Scalar, Options, JointCollectionTpl > &model) |
Return the neutral configuration element related to the model configuration space. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > | neutral (const ModelTpl< Scalar, Options, JointCollectionTpl > &model) |
Return the neutral configuration element related to the model configuration space. More... | |
Main pinocchio namespace.
typedef SpatialAxis<0> pinocchio::AxisVX |
Definition at line 140 of file spatial-axis.hpp.
typedef SpatialAxis<1> pinocchio::AxisVY |
Definition at line 141 of file spatial-axis.hpp.
typedef SpatialAxis<2> pinocchio::AxisVZ |
Definition at line 142 of file spatial-axis.hpp.
typedef SpatialAxis<3> pinocchio::AxisWX |
Definition at line 144 of file spatial-axis.hpp.
typedef SpatialAxis<4> pinocchio::AxisWY |
Definition at line 145 of file spatial-axis.hpp.
typedef SpatialAxis<5> pinocchio::AxisWZ |
Definition at line 146 of file spatial-axis.hpp.
typedef CartesianAxis<0> pinocchio::AxisX |
Definition at line 143 of file cartesian-axis.hpp.
typedef CartesianAxis<1> pinocchio::AxisY |
Definition at line 144 of file cartesian-axis.hpp.
typedef CartesianAxis<2> pinocchio::AxisZ |
Definition at line 145 of file cartesian-axis.hpp.
typedef CartesianProductOperationVariantTpl<double, 0, LieGroupCollectionDefaultTpl> pinocchio::CartesianProductOperationVariant |
Definition at line 18 of file cartesian-product-variant.hpp.
typedef ConstraintTpl<1,double,0> pinocchio::Constraint1d |
Definition at line 13 of file constraint.hpp.
typedef ConstraintTpl<3,double,0> pinocchio::Constraint3d |
Definition at line 16 of file constraint.hpp.
typedef ConstraintTpl<6,double,0> pinocchio::Constraint6d |
Definition at line 17 of file constraint.hpp.
typedef ConstraintTpl<Eigen::Dynamic,double,0> pinocchio::ConstraintXd |
Definition at line 18 of file constraint.hpp.
typedef ForceSetTpl<double,0> pinocchio::ForceSet |
Definition at line 156 of file force-set.hpp.
typedef GeometryPoolTpl<double,0,JointCollectionDefaultTpl> pinocchio::GeometryPool |
Definition at line 154 of file src/multibody/pool/geometry.hpp.
typedef JointTpl<double> pinocchio::Joint |
Definition at line 19 of file joint-generic.hpp.
typedef JointDataPrismaticTpl<double,0,0> pinocchio::JointDataPX |
Definition at line 652 of file joint-prismatic.hpp.
typedef JointDataPrismaticTpl<double,0,1> pinocchio::JointDataPY |
Definition at line 656 of file joint-prismatic.hpp.
typedef JointDataPrismaticTpl<double,0,2> pinocchio::JointDataPZ |
Definition at line 660 of file joint-prismatic.hpp.
typedef JointDataRevoluteUnboundedTpl<double,0,0> pinocchio::JointDataRUBX |
Definition at line 203 of file joint-revolute-unbounded.hpp.
typedef JointDataRevoluteUnboundedTpl<double,0,1> pinocchio::JointDataRUBY |
Definition at line 207 of file joint-revolute-unbounded.hpp.
typedef JointDataRevoluteUnboundedTpl<double,0,2> pinocchio::JointDataRUBZ |
Definition at line 211 of file joint-revolute-unbounded.hpp.
typedef JointDataRevoluteTpl<double,0,0> pinocchio::JointDataRX |
Definition at line 755 of file joint-revolute.hpp.
typedef JointDataRevoluteTpl<double,0,1> pinocchio::JointDataRY |
Definition at line 759 of file joint-revolute.hpp.
typedef JointDataRevoluteTpl<double,0,2> pinocchio::JointDataRZ |
Definition at line 763 of file joint-revolute.hpp.
Definition at line 149 of file joint-collection.hpp.
typedef JointModelPrismaticTpl<double,0,0> pinocchio::JointModelPX |
Definition at line 653 of file joint-prismatic.hpp.
typedef JointModelPrismaticTpl<double,0,1> pinocchio::JointModelPY |
Definition at line 657 of file joint-prismatic.hpp.
typedef JointModelPrismaticTpl<double,0,2> pinocchio::JointModelPZ |
Definition at line 661 of file joint-prismatic.hpp.
typedef JointModelRevoluteUnboundedTpl<double,0,0> pinocchio::JointModelRUBX |
Definition at line 204 of file joint-revolute-unbounded.hpp.
typedef JointModelRevoluteUnboundedTpl<double,0,1> pinocchio::JointModelRUBY |
Definition at line 208 of file joint-revolute-unbounded.hpp.
typedef JointModelRevoluteUnboundedTpl<double,0,2> pinocchio::JointModelRUBZ |
Definition at line 212 of file joint-revolute-unbounded.hpp.
typedef JointModelRevoluteTpl<double,0,0> pinocchio::JointModelRX |
Definition at line 756 of file joint-revolute.hpp.
typedef JointModelRevoluteTpl<double,0,1> pinocchio::JointModelRY |
Definition at line 760 of file joint-revolute.hpp.
typedef JointModelRevoluteTpl<double,0,2> pinocchio::JointModelRZ |
Definition at line 764 of file joint-revolute.hpp.
Definition at line 148 of file joint-collection.hpp.
typedef JointPrismaticTpl<double,0,0> pinocchio::JointPX |
Definition at line 651 of file joint-prismatic.hpp.
typedef JointPrismaticTpl<double,0,1> pinocchio::JointPY |
Definition at line 655 of file joint-prismatic.hpp.
typedef JointPrismaticTpl<double,0,2> pinocchio::JointPZ |
Definition at line 659 of file joint-prismatic.hpp.
typedef JointRevoluteUnboundedTpl<double,0,0> pinocchio::JointRUBX |
Definition at line 202 of file joint-revolute-unbounded.hpp.
typedef JointRevoluteUnboundedTpl<double,0,1> pinocchio::JointRUBY |
Definition at line 206 of file joint-revolute-unbounded.hpp.
typedef JointRevoluteUnboundedTpl<double,0,2> pinocchio::JointRUBZ |
Definition at line 210 of file joint-revolute-unbounded.hpp.
typedef JointRevoluteTpl<double,0,0> pinocchio::JointRX |
Definition at line 754 of file joint-revolute.hpp.
typedef JointRevoluteTpl<double,0,1> pinocchio::JointRY |
Definition at line 758 of file joint-revolute.hpp.
typedef JointRevoluteTpl<double,0,2> pinocchio::JointRZ |
Definition at line 762 of file joint-revolute.hpp.
typedef LieGroupCollectionDefaultTpl<double> pinocchio::LieGroupCollectionDefault |
Definition at line 36 of file liegroup-collection.hpp.
typedef ModelPoolTpl<double,0,JointCollectionDefaultTpl> pinocchio::ModelPool |
Definition at line 156 of file src/multibody/pool/model.hpp.
typedef MotionPlanarTpl<double> pinocchio::MotionPlanar |
Definition at line 19 of file joint-planar.hpp.
typedef MotionPrismaticUnalignedTpl<double> pinocchio::MotionPrismaticUnaligned |
Definition at line 19 of file joint-prismatic-unaligned.hpp.
typedef MotionRevoluteUnalignedTpl<double> pinocchio::MotionRevoluteUnaligned |
Definition at line 18 of file joint-revolute-unaligned.hpp.
typedef MotionSphericalTpl<double> pinocchio::MotionSpherical |
Definition at line 19 of file joint-spherical.hpp.
typedef MotionTranslationTpl<double> pinocchio::MotionTranslation |
Definition at line 18 of file joint-translation.hpp.
anonymous enum |
Enumerator | |
---|---|
MAX_JOINT_NV |
Definition at line 14 of file src/multibody/joint/fwd.hpp.
anonymous enum |
Enumerator | |
---|---|
SELF |
Definition at line 17 of file liegroup-base.hpp.
Argument position. Used as template parameter to refer to an argument.
Enumerator | |
---|---|
ARG0 | |
ARG1 | |
ARG2 | |
ARG3 | |
ARG4 |
Definition at line 59 of file src/fwd.hpp.
Enumerator | |
---|---|
SETTO | |
ADDTO | |
RMTO |
Definition at line 68 of file src/fwd.hpp.
enum pinocchio::FrameType |
Enum on the possible types of frames.
All other frame types are defined for user convenience and code readability, to also keep track of the information usually stored within URDF models.
See also https://wiki.ros.org/urdf/XML/joint, https://wiki.ros.org/urdf/XML/link and https://wiki.ros.org/urdf/XML/sensor.
Definition at line 28 of file src/multibody/frame.hpp.
void pinocchio::aba | ( | const int | num_threads, |
ModelPoolTpl< Scalar, Options, JointCollectionTpl > & | pool, | ||
const Eigen::MatrixBase< ConfigVectorPool > & | q, | ||
const Eigen::MatrixBase< TangentVectorPool1 > & | v, | ||
const Eigen::MatrixBase< TangentVectorPool2 > & | tau, | ||
const Eigen::MatrixBase< TangentVectorPool3 > & | a | ||
) |
A parallel version of the Articulated Body algorithm. It computes the forward dynamics, aka the joint acceleration according to the current state of the system and the desired joint torque.
JointCollection | Collection of Joint types. |
ConfigVectorPool | Matrix type of the joint configuration vector. |
TangentVectorPool1 | Matrix type of the joint velocity vector. |
TangentVectorPool2 | Matrix type of the joint torque vector. |
TangentVectorPool3 | Matrix type of the joint acceleration vector. |
[in] | pool | Pool containing model and data for parallel computations. |
[in] | num_threads | Number of threads used for parallel computations. |
[in] | q | The joint configuration vector (dim model.nq x batch_size). |
[in] | v | The joint velocity vector (dim model.nv x batch_size). |
[in] | tau | The joint acceleration vector (dim model.nv x batch_size). |
[out] | a | The joint torque vector (dim model.nv x batch_size). |
Definition at line 32 of file algorithm/parallel/aba.hpp.
|
inline |
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
|
inline |
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
ForceDerived | Type of the external forces. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[in] | fext | Vector of external forces expressed in the local frame of the joints (dim model.njoints) |
void pinocchio::addJointAndBody | ( | Model & | model, |
const JointModelBase< D > & | jmodel, | ||
const Model::JointIndex | parent_id, | ||
const SE3 & | joint_placement, | ||
const std::string & | name, | ||
const Inertia & | Y | ||
) |
Definition at line 11 of file model-generator.hpp.
|
inline |
void pinocchio::alphaSkew | ( | const Scalar | alpha, |
const Eigen::MatrixBase< Vector3 > & | v, | ||
const Eigen::MatrixBase< Matrix3 > & | M | ||
) |
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( )
[in] | alpha | a real scalar. |
[in] | v | a vector of dimension 3. |
[out] | M | the skew matrix representation of dimension 3x3. |
|
inline |
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( )
[in] | alpha | a real scalar. |
[in] | v | a vector of dimension 3. |
|
inline |
Append geom_model2 to geom_model1
The steps for appending are:
[out] | geom_model1 | geometry model where the data is added |
[in] | geom_model2 | geometry model from which new geometries are taken |
void pinocchio::appendModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelA, |
const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelB, | ||
const FrameIndex | frameInModelA, | ||
const SE3Tpl< Scalar, Options > & | aMb, | ||
ModelTpl< Scalar, Options, JointCollectionTpl > & | model | ||
) |
Append a child model into a parent model, after a specific frame given by its index.
[in] | modelA | the parent model. |
[in] | modelB | the child model. |
[in] | frameInModelA | index of the frame of modelA where to append modelB. |
[in] | aMb | pose of modelB universe joint (index 0) in frameInModelA. |
[out] | model | the resulting model. |
ModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::appendModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelA, |
const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelB, | ||
const FrameIndex | frameInModelA, | ||
const SE3Tpl< Scalar, Options > & | aMb | ||
) |
Append a child model into a parent model, after a specific frame given by its index.
[in] | modelA | the parent model. |
[in] | modelB | the child model. |
[in] | frameInModelA | index of the frame of modelA where to append modelB. |
[in] | aMb | pose of modelB universe joint (index 0) in frameInModelA. |
Definition at line 44 of file src/algorithm/model.hpp.
void pinocchio::appendModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelA, |
const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelB, | ||
const GeometryModel & | geomModelA, | ||
const GeometryModel & | geomModelB, | ||
const FrameIndex | frameInModelA, | ||
const SE3Tpl< Scalar, Options > & | aMb, | ||
ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | ||
GeometryModel & | geomModel | ||
) |
Append a child model into a parent model, after a specific frame given by its index.
[in] | modelA | the parent model. |
[in] | modelB | the child model. |
[in] | frameInModelA | index of the frame of modelA where to append modelB. |
[in] | aMb | pose of modelB universe joint (index 0) in frameInModelA. |
[out] | model | the resulting model. |
[in] | geomModelA | the parent geometry model. |
[in] | geomModelB | the child geometry model. |
[out] | geomModel | the resulting geometry model. |
PINOCCHIO_DLLAPI void pinocchio::appendSuffixToPaths | ( | std::vector< std::string > & | list_of_paths, |
const std::string & | suffix | ||
) |
For a given vector of paths, add a suffix inplace to each path and return the vector inplace.
[in,out] | list_of_paths | The vector of path names. |
[in] | suffix | Suffix to be added to each element of the path names. |
Definition at line 46 of file file-explorer.cpp.
|
inline |
Generate the label (X, Y or Z) of the axis relative to its index.
axis | Index of the axis (either 0 for X, 1 for Y and Z for 2). |
|
inline |
Definition at line 20 of file axis-label.hpp.
|
inline |
Definition at line 21 of file axis-label.hpp.
|
inline |
Definition at line 22 of file axis-label.hpp.
|
inline |
Visit a JointDataTpl through JointBiasVisitor to get the joint bias as a dense motion.
[in] | jdata | The joint data to visit. |
|
inline |
Computes the regressor for the dynamic parameters of a single rigid body.
The result is such that
[in] | v | Velocity of the rigid body |
[in] | a | Acceleration of the rigid body |
[out] | regressor | The resulting regressor of the body. |
|
inline |
Computes the regressor for the dynamic parameters of a single rigid body.
The result is such that
[in] | v | Velocity of the rigid body |
[in] | a | Acceleration of the rigid body |
void pinocchio::buildAllJointsModel | ( | Model & | model | ) |
Definition at line 33 of file model-generator.hpp.
void pinocchio::buildReducedModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
std::vector< JointIndex > | list_of_joints_to_lock, | ||
const Eigen::MatrixBase< ConfigVectorType > & | reference_configuration, | ||
ModelTpl< Scalar, Options, JointCollectionTpl > & | reduced_model | ||
) |
Build a reduced model from a given input model and a list of joint to lock.
[in] | model | the input model to reduce. |
[in] | list_of_joints_to_lock | list of joints to lock in the input model. |
[in] | reference_configuration | reference configuration. |
[out] | reduced_model | the reduced model. |
ModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::buildReducedModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const std::vector< JointIndex > & | list_of_joints_to_lock, | ||
const Eigen::MatrixBase< ConfigVectorType > & | reference_configuration | ||
) |
Build a reduced model from a given input model and a list of joint to lock.
[in] | model | the input model to reduce. |
[in] | list_of_joints_to_lock | list of joints to lock in the input model. |
[in] | reference_configuration | reference configuration. |
Definition at line 112 of file src/algorithm/model.hpp.
void pinocchio::buildReducedModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const GeometryModel & | geom_model, | ||
const std::vector< JointIndex > & | list_of_joints_to_lock, | ||
const Eigen::MatrixBase< ConfigVectorType > & | reference_configuration, | ||
ModelTpl< Scalar, Options, JointCollectionTpl > & | reduced_model, | ||
GeometryModel & | reduced_geom_model | ||
) |
Build a reduced model and a rededuced geometry model from a given input model, a given input geometry model and a list of joint to lock.
[in] | model | the input model to reduce. |
[in] | geom_model | the input geometry model to reduce. |
[in] | list_of_joints_to_lock | list of joints to lock in the input model. |
[in] | reference_configuration | reference configuration. |
[out] | reduced_model | the reduced model. |
[out] | reduced_geom_model | the reduced geometry model. |
void pinocchio::buildReducedModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const std::vector< GeometryModel, GeometryModelAllocator > & | list_of_geom_models, | ||
const std::vector< JointIndex > & | list_of_joints_to_lock, | ||
const Eigen::MatrixBase< ConfigVectorType > & | reference_configuration, | ||
ModelTpl< Scalar, Options, JointCollectionTpl > & | reduced_model, | ||
std::vector< GeometryModel, GeometryModelAllocator > & | list_of_reduced_geom_models | ||
) |
Build a reduced model and a rededuced geometry model from a given input model, a given input geometry model and a list of joint to lock.
[in] | model | the input model to reduce. |
[in] | list_of_geom_models | the input geometry model to reduce (example: visual_model, collision_model). |
[in] | list_of_joints_to_lock | list of joints to lock in the input model. |
[in] | reference_configuration | reference configuration. |
[out] | reduced_model | the reduced model. |
[out] | list_of_reduced_geom_model | the list of reduced geometry models. |
|
inline |
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to.
JointCollection | Collection of Joint types. |
Matrix6Type | A matrix 6x6 like Eigen container. |
[in] | jmodel | The corresponding JointModelVariant to the JointDataVariant we want to update |
[in,out] | jdata | The JointDataVariant we want to update |
[in,out] | I | Inertia matrix of the subtree following the jmodel in the kinematic chain as dense matrix |
[in] | update_I | If I should be updated or not |
|
inline |
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcFirstOrderVisitor to compute the joint data kinematics at order one.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | jmodel | The corresponding JointModelVariant to the JointDataVariant we want to update |
jdata | The JointDataVariant we want to update | |
[in] | q | The full model's (in which the joint belongs to) configuration vector |
[in] | v | The full model's (in which the joint belongs to) velocity vector |
|
inline |
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcZeroOrderVisitor to compute the joint data kinematics at order zero.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | jmodel | The corresponding JointModelVariant to the JointDataVariant we want to update |
jdata | The JointDataVariant we want to update | |
[in] | q | The full model's (in which the joint belongs to) configuration vector |
NewScalar pinocchio::cast | ( | const Scalar & | value | ) |
CastType< NewScalar,JointModelTpl<Scalar,Options,JointCollectionTpl> >::type pinocchio::cast_joint | ( | const JointModelTpl< Scalar, Options, JointCollectionTpl > & | jmodel | ) |
Visit a JointModelTpl<Scalar,...> to cast it into JointModelTpl<NewScalar,...>
NewScalar | new scalar type of of the JointModelTpl |
[in] | jmodel | The joint model to cast. |
|
inline |
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal momenta according to the current joint configuration and velocity.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
|
inline |
Computes the center of mass position of a given model according to a particular joint configuration. The result is accessible through data.com[0] for the full body com and data.com[i] for the subtree supported by joint i (expressed in the joint i frame).
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | computeSubtreeComs | If true, the algorithm computes also the center of mass of the subtrees. |
|
inline |
Computes the center of mass position and velocity of a given model according to a particular joint configuration and velocity. The result is accessible through data.com[0], data.vcom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame).
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | computeSubtreeComs | If true, the algorithm computes also the center of mass of the subtrees. |
|
inline |
Computes the center of mass position, velocity and acceleration of a given model according to a particular joint configuration, velocity and acceleration. The result is accessible through data.com[0], data.vcom[0], data.acom[0] for the full body com position, velocity and acceleation. And data.com[i], data.vcom[i] and data.acom[i] for the subtree supported by joint i (expressed in the joint i frame).
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[in] | computeSubtreeComs | If true, the algorithm computes also the center of mass of the subtrees. |
const DataTpl<Scalar,Options,JointCollectionTpl>::Vector3& pinocchio::centerOfMass | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
KinematicLevel | kinematic_level, | ||
const bool | computeSubtreeComs = true |
||
) |
Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data and the requested kinematic_level. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame).
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | kinematic_level | if = POSITION, computes the CoM position, if = VELOCITY, also computes the CoM velocity and if = ACCELERATION, it also computes the CoM acceleration. |
[in] | computeSubtreeComs | If true, the algorithm computes also the center of mass of the subtrees. |
|
inline |
Definition at line 146 of file center-of-mass.hpp.
const DataTpl<Scalar,Options,JointCollectionTpl>::Vector3& pinocchio::centerOfMass | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const bool | computeSubtreeComs = true |
||
) |
Computes the center of mass position, velocity and acceleration of a given model according to the current kinematic values contained in data. The result is accessible through data.com[0], data.vcom[0] and data.acom[0] for the full body com position and velocity. And data.com[i] and data.vcom[i] for the subtree supported by joint i (expressed in the joint i frame).
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | computeSubtreeComs | If true, the algorithm computes also the center of mass of the subtrees, expressed in the local coordinate frame of each joint. |
Definition at line 167 of file center-of-mass.hpp.
|
inline |
Check the validity of data wrt to model, in particular if model has been modified.
[in] | model | reference model |
[in] | data | corresponding data |
|
inline |
|
inline |
Checks if the current version of Pinocchio is at least the version provided by the input arguments.
[in] | major_version | Major version to check. |
[in] | minor_version | Minor version to check. |
[in] | patch_version | Patch version to check. |
Definition at line 42 of file src/utils/version.hpp.
|
inline |
The derivatives of the Articulated-Body algorithm.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
MatrixType1 | Type of the matrix containing the partial derivative with respect to the joint configuration vector. |
MatrixType2 | Type of the matrix containing the partial derivative with respect to the joint velocity vector. |
MatrixType3 | Type of the matrix containing the partial derivative with respect to the joint torque vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[out] | aba_partial_dq | Partial derivative of the generalized torque vector with respect to the joint configuration. |
[out] | aba_partial_dv | Partial derivative of the generalized torque vector with respect to the joint velocity. |
[out] | aba_partial_dtau | Partial derivative of the generalized torque vector with respect to the joint torque. |
|
inline |
The derivatives of the Articulated-Body algorithm with external forces.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
MatrixType1 | Type of the matrix containing the partial derivative with respect to the joint configuration vector. |
MatrixType2 | Type of the matrix containing the partial derivative with respect to the joint velocity vector. |
MatrixType3 | Type of the matrix containing the partial derivative with respect to the joint torque vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[in] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
[out] | aba_partial_dq | Partial derivative of the generalized torque vector with respect to the joint configuration. |
[out] | aba_partial_dv | Partial derivative of the generalized torque vector with respect to the joint velocity. |
[out] | aba_partial_dtau | Partial derivative of the generalized torque vector with respect to the joint torque. |
|
inline |
The derivatives of the Articulated-Body algorithm.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
Definition at line 105 of file aba-derivatives.hpp.
|
inline |
The derivatives of the Articulated-Body algorithm with external forces.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[in] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
Definition at line 137 of file aba-derivatives.hpp.
|
inline |
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the same time to:
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
|
inline |
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center of mass.
Scalar | The scalar type. |
Options | Eigen Alignment options. |
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
Definition at line 70 of file centroidal.hpp.
|
inline |
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and its time derivative expressed around the center of mass.
Scalar | The scalar type. |
Options | Eigen Alignment options. |
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
Definition at line 138 of file centroidal.hpp.
|
inline |
Computes the analytical derivatives of the centroidal dynamics with respect to the joint configuration vector, velocity and acceleration.
Computes the first order approximation of the centroidal dynamics time derivative and corresponds to the following equation
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[out] | dh_dq | The partial derivative of the centroidal momentum with respect to the configuration vector (dim 6 x model.nv). |
[out] | dhdot_dq | The partial derivative of the centroidal dynamics with respect to the configuration vector (dim 6 x model.nv). |
[out] | dhdot_dv | The partial derivative of the centroidal dynamics with respect to the velocity vector (dim 6 x model.nv). |
[out] | dhdot_da | The partial derivative of the centroidal dynamics with respect to the acceleration vector (dim 6 x model.nv). |
|
inline |
Computes the Centroidal Momentum Matrix,.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
Computes the Centroidal Momentum Matrix time derivative.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
|
inline |
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center of mass.
Scalar | The scalar type. |
Options | Eigen Alignment options. |
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center of mass.
Scalar | The scalar type. |
Options | Eigen Alignment options. |
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
Definition at line 53 of file centroidal.hpp.
|
inline |
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and its time derivative expressed around the center of mass.
Scalar | The scalar type. |
Options | Eigen Alignment options. |
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and its time derivative expressed around the center of mass.
Scalar | The scalar type. |
Options | Eigen Alignment options. |
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
Definition at line 120 of file centroidal.hpp.
|
inline |
Definition at line 16 of file src/algorithm/parallel/geometry.hpp.
bool pinocchio::computeCollisions | ( | const int | num_threads, |
const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | ||
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const GeometryModel & | geom_model, | ||
GeometryData & | geom_data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const bool | stopAtFirstCollision = false |
||
) |
Definition at line 60 of file src/algorithm/parallel/geometry.hpp.
void pinocchio::computeCollisions | ( | const int | num_threads, |
GeometryPoolTpl< Scalar, Options, JointCollectionTpl > & | pool, | ||
const Eigen::MatrixBase< ConfigVectorPool > & | q, | ||
const Eigen::MatrixBase< CollisionVectorResult > & | res, | ||
const bool | stopAtFirstCollision = false |
||
) |
Definition at line 73 of file src/algorithm/parallel/geometry.hpp.
|
inline |
Computes the Coriolis Matrix of the Lagrangian dynamics:
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
|
inline |
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acceleration for any joint of the model.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v | The joint velocity (vector dim model.nv). |
|
inline |
Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | frameId | The id of the Frame refering to model.frames[frameId]. |
[in] | reference_frame | Reference frame in which the Jacobian is expressed. |
[out] | J | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill J with zero elements, e.g. J.setZero(). |
|
inline |
Computes the Jacobian of a specific Frame expressed in the LOCAL frame coordinate system.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | frameId | The id of the Frame refering to model.frames[frameId]. |
[out] | J | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill J with zero elements, e.g. J.setZero(). |
Definition at line 218 of file frames.hpp.
void pinocchio::computeFrameKinematicRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xReturnType > & | kinematic_regressor | ||
) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the frame given as input.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | frame_id | Index of the frame. |
[in] | rf | Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD). |
[out] | kinematic_regressor | The kinematic regressor containing the result. Matrix of size 6*(model.njoints-1) initialized to 0. |
DataTpl<Scalar,Options,JointCollectionTpl>::Matrix6x pinocchio::computeFrameKinematicRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | rf | ||
) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the frame given as input.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | frame_id | Index of the frame. |
[in] | rf | Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD). |
Definition at line 119 of file regressor.hpp.
|
inline |
Computes the generalized gravity contribution of the Lagrangian dynamics:
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
Computes the partial derivative of the generalized gravity contribution with respect to the joint configuration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
ReturnMatrixType | Type of the matrix containing the partial derivative of the gravity vector with respect to the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[out] | gravity_partial_dq | Partial derivative of the generalized gravity vector with respect to the joint configuration. |
|
inline |
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.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | jointId | The id of the joint refering to model.joints[jointId]. |
[out] | J | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill J with zero elements, e.g. J.setZero(). |
|
inline |
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.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
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.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
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.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
|
inline |
Computes all the terms required to compute the second order derivatives of the placement information, also know as the kinematic Hessian. This function assumes that the joint Jacobians (a.k.a data.J) has been computed first. See computeJointJacobians for such a function.
Scalar | Scalar type of the kinematic model. |
Options | Alignement options of the kinematic model. |
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Computes all the terms required to compute the second order derivatives of the placement information, also know as the kinematic Hessian.
Scalar | Scalar type of the kinematic model. |
Options | Alignement options of the kinematic model. |
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
Definition at line 164 of file kinematics-derivatives.hpp.
void pinocchio::computeJointKinematicRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | rf, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const Eigen::MatrixBase< Matrix6xReturnType > & | kinematic_regressor | ||
) |
Computes the kinematic regressor that links the joint placements variations of the whole kinematic tree to the placement variation of the frame rigidly attached to the joint and given by its placement w.r.t. to the joint frame.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | Index of the joint. |
[in] | rf | Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD). |
[in] | placement | Relative placement to the joint frame. |
[out] | kinematic_regressor | The kinematic regressor containing the result. Matrix of size 6*(model.njoints-1) initialized to 0. |
DataTpl<Scalar,Options,JointCollectionTpl>::Matrix6x pinocchio::computeJointKinematicRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | rf, | ||
const SE3Tpl< Scalar, Options > & | placement | ||
) |
Computes the kinematic regressor that links the joint placements variations of the whole kinematic tree to the placement variation of the frame rigidly attached to the joint and given by its placement w.r.t. to the joint frame.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | Index of the joint. |
[in] | rf | Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD). |
[in] | placement | Relative placement to the joint frame. |
Definition at line 42 of file regressor.hpp.
void pinocchio::computeJointKinematicRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xReturnType > & | kinematic_regressor | ||
) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the joint given as input.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | Index of the joint. |
[in] | rf | Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD). |
[out] | kinematic_regressor | The kinematic regressor containing the result. Matrix of size 6*(model.njoints-1) initialized to 0. |
DataTpl<Scalar,Options,JointCollectionTpl>::Matrix6x pinocchio::computeJointKinematicRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | rf | ||
) |
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tree to the placement variation of the joint given as input.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | Index of the joint. |
[in] | rf | Reference frame in which the result is expressed (LOCAL, LOCAL_WORLD_ALIGNED or WORLD). |
Definition at line 81 of file regressor.hpp.
|
inline |
Computes the joint torque regressor that links the joint torque to the dynamic parameters of each link according to the current the robot motion.
The result is stored in data.jointTorqueRegressor
and it corresponds to a matrix such that where and
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
|
inline |
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
Definition at line 48 of file energy.hpp.
void pinocchio::computeKKTContactDynamicMatrixInverse | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< ConstraintMatrixType > & | J, | ||
const Eigen::MatrixBase< KKTMatrixType > & | KKTMatrix_inv, | ||
const Scalar & | inv_damping = 0. |
||
) |
Computes the inverse of the KKT matrix for dynamics with contact constraints. It computes the following matrix:
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | J | Jacobian of the constraints. |
[out] | KKTMatrix_inv | inverse of the MJtJ matrix. |
[in] | inv_damping | regularization coefficient. |
|
inline |
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field. The result is accessible through data.potential_energy.
JointCollection | Collection of Joint types. |
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field. The result is accessible through data.potential_energy.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
Definition at line 131 of file energy.hpp.
|
inline |
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
MatrixType1 | Type of the matrix containing the partial derivative with respect to the joint configuration vector. |
MatrixType2 | Type of the matrix containing the partial derivative with respect to the joint velocity vector. |
MatrixType3 | Type of the matrix containing the partial derivative with respect to the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[out] | rnea_partial_dq | Partial derivative of the generalized torque vector with respect to the joint configuration. |
[out] | rnea_partial_dv | Partial derivative of the generalized torque vector with respect to the joint velocity. |
[out] | rnea_partial_da | Partial derivative of the generalized torque vector with respect to the joint acceleration. |
|
inline |
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
MatrixType1 | Type of the matrix containing the partial derivative with respect to the joint configuration vector. |
MatrixType2 | Type of the matrix containing the partial derivative with respect to the joint velocity vector. |
MatrixType3 | Type of the matrix containing the partial derivative with respect to the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[in] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
[out] | rnea_partial_dq | Partial derivative of the generalized torque vector with respect to the joint configuration. |
[out] | rnea_partial_dv | Partial derivative of the generalized torque vector with respect to the joint velocity. |
[out] | rnea_partial_da | Partial derivative of the generalized torque vector with respect to the joint acceleration. |
|
inline |
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
Definition at line 167 of file rnea-derivatives.hpp.
|
inline |
Computes the derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[in] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
Definition at line 201 of file rnea-derivatives.hpp.
|
inline |
Computes the Second-Order partial derivatives of the Recursive Newton Euler Algorithm w.r.t the joint configuration, the joint velocity and the joint acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
Tensor1 | Type of the 3D-Tensor containing the SO partial derivative with respect to the joint configuration vector. The elements of Torque vector are along the 1st dim, and joint config along 2nd,3rd dimensions. |
Tensor2 | Type of the 3D-Tensor containing the Second-Order partial derivative with respect to the joint velocity vector. The elements of Torque vector are along the 1st dim, and the velocity along 2nd,3rd dimensions. |
Tensor3 | Type of the 3D-Tensor containing the cross Second-Order partial derivative with respect to the joint configuration and velocty vector. The elements of Torque vector are along the 1st dim, and the config. vector along 2nd dimension, and velocity along the third dimension. |
Tensor4 | Type of the 3D-Tensor containing the cross Second-Order partial derivative with respect to the joint configuration and acceleration vector. This is also the First-order partial derivative of Mass-Matrix (M) with respect to configuration vector. The elements of Torque vector are along the 1st dim, and the acceleration vector along 2nd dimension, while configuration along the third dimension. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[out] | d2tau_dqdq | Second-Order Partial derivative of the generalized torque vector with respect to the joint configuration. |
[out] | d2tau_dvdv | Second-Order Partial derivative of the generalized torque vector with respect to the joint velocity |
[out] | dtau_dqdv | Cross Second-Order Partial derivative of the generalized torque vector with respect to the joint configuration and velocity. |
[out] | dtau_dadq | Cross Second-Order Partial derivative of the generalized torque vector with respect to the joint configuration and accleration. |
|
inline |
Computes the Second-Order partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint configuration, the joint velocity and the joint acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
Definition at line 126 of file rnea-second-order-derivatives.hpp.
|
inline |
Computes the static regressor that links the center of mass positions of all the links to the center of mass of the complete model according to the current configuration of the robot.
The result is stored in data.staticRegressor
and it corresponds to a matrix such that where and
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
Definition at line 176 of file regressor.hpp.
|
inline |
Computes the generalized static torque contribution of the Lagrangian dynamics:
. This torque vector accouts for the contribution of the gravity and the external forces.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
|
inline |
Computes the partial derivative of the generalized gravity and external forces contributions (a.k.a static torque vector) with respect to the joint configuration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
ReturnMatrixType | Type of the matrix containing the partial derivative of the gravity vector with respect to the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
[out] | static_torque_partial_dq | Partial derivative of the static torque vector with respect to the joint configuration. |
|
inline |
Compute the mass of each kinematic subtree and store it in data.mass. The element mass[0] corresponds to the total mass of the model.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
ForceTpl<Scalar, Options> pinocchio::computeSupportedForceByFrame | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id | ||
) |
Computes the force supported by a specific frame (given by frame_id) expressed in the LOCAL frame. The supported force corresponds to the sum of all the forces experienced after the given frame, i.e :
data.f[joint_id]
, after having call pinocchio::rnea.JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | frameId | The index of the frame. |
InertiaTpl<Scalar, Options> pinocchio::computeSupportedInertiaByFrame | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
bool | with_subtree | ||
) |
Compute the inertia supported by a specific frame (given by frame_id) expressed in the LOCAL frame. The total supported inertia corresponds to the sum of all the inertia after the given frame, i.e :
data.Ycrb[joint_id]
, after having called pinocchio::crba (if with_subtree == true).model.inertia[joint_id]
(if with_subtree == false).JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | frameId | The index of the frame. |
[in] | with_subtree | If false, compute the inertia only inside the frame parent joint if false. If true, include child joints inertia. |
|
inline |
Compute the total mass of the model and return it.
[in] | model | The model structure of the rigid body system. |
|
inline |
Compute the total mass of the model, put it in data.mass[0] and return it.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Visit a JointDataVariant through JointConstraintVisitor to get the joint constraint as a dense constraint.
[in] | jdata | The joint data to visit. |
|
inline |
Copy part of the data from origin
to dest
. Template parameter can be used to select at which differential level the copy should occur.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | orig | Data from which the values are copied. |
[out] | dest | Data to which the values are copied |
[in] | kinematic_level | if =0, copy oMi. If =1, also copy v. If =2, also copy a, a_gf and f. |
|
inline |
|
inline |
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid Body Algorithm (Chapter 6, Rigid-Body Dynamics Algorithms, R. Featherstone, 2008). The result is accessible through data.M.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid Body Algorithm (Chapter 6, Rigid-Body Dynamics Algorithms, R. Featherstone, 2008). The result is accessible through data.M.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.
JointCollection | Collection of Joint types. |
[in] | jmodel | The JointModelTpl we want to create a data for. |
|
inline |
|
inline |
Computes the time derivative of the Centroidal Momentum Matrix according to the current configuration and velocity vectors.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
void pinocchio::dDifference | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< ConfigL_t > & | q0, | ||
const Eigen::MatrixBase< ConfigR_t > & | q1, | ||
const Eigen::MatrixBase< JacobianOut_t > & | J, | ||
const ArgumentPosition | arg | ||
) |
void pinocchio::dDifference | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< ConfigL_t > & | q0, | ||
const Eigen::MatrixBase< ConfigR_t > & | q1, | ||
const Eigen::MatrixBase< JacobianIn_t > & | Jin, | ||
int | self, | ||
const Eigen::MatrixBase< JacobianOut_t > & | Jout | ||
) |
void pinocchio::dDifference | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< ConfigL_t > & | q0, | ||
const Eigen::MatrixBase< ConfigR_t > & | q1, | ||
int | self, | ||
const Eigen::MatrixBase< JacobianIn_t > & | Jin, | ||
const Eigen::MatrixBase< JacobianOut_t > & | Jout | ||
) |
void pinocchio::dDifference | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVector1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVector2 > & | q1, | ||
const Eigen::MatrixBase< JacobianMatrix > & | J, | ||
const ArgumentPosition | arg | ||
) |
Computes the Jacobian of a small variation of the configuration vector into the tangent space at identity.
This jacobian has to be interpreted in terms of Lie group, not vector space: as such, it is expressed in the tangent space only, not the configuration space. Calling the difference function, these jacobians satisfy the following relationships in the tangent space:
[in] | model | Model of the kinematic tree on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Joint velocity (size model.nv) |
[out] | J | Jacobian of the Difference operation, either with respect to q0 or q1 (size model.nv x model.nv). |
[in] | arg | Argument (either q0 or q1) with respect to which the differentiation is performed. |
Definition at line 507 of file joint-configuration.hpp.
void pinocchio::dDifference | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVector1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVector2 > & | q1, | ||
const Eigen::MatrixBase< JacobianMatrix > & | J, | ||
const ArgumentPosition | arg | ||
) |
Computes the Jacobian of a small variation of the configuration vector into the tangent space at identity.
This jacobian has to be interpreted in terms of Lie group, not vector space: as such, it is expressed in the tangent space only, not the configuration space. Calling the difference function, these jacobians satisfy the following relationships in the tangent space:
[in] | model | Model of the kinematic tree on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Joint velocity (size model.nv) |
[out] | J | Jacobian of the Difference operation, either with respect to q0 or q1 (size model.nv x model.nv). |
[in] | arg | Argument (either q0 or q1) with respect to which the differentiation is performed. |
Definition at line 507 of file joint-configuration.hpp.
|
inline |
void pinocchio::difference | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1, | ||
const Eigen::MatrixBase< ReturnType > & | dvout | ||
) |
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1.
This function corresponds to the log map of the joint configuration Lie Group. Its output can be interpreted as a difference from the joint configuration space to the Lie algebra .
[in] | model | Model of the system on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Desired configuration (size model.nq) |
[out] | dvout | The corresponding velocity (size model.nv) |
This function corresponds to the log map of the joint configuration Lie Group. Its output can be interpreted as a difference from the joint configuration space to the Lie algebra .
[in] | model | Model of the system on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Desired configuration (size model.nq) |
[out] | dvout | The corresponding velocity (size model.nv). |
Definition at line 142 of file joint-configuration.hpp.
void pinocchio::difference | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1, | ||
const Eigen::MatrixBase< ReturnType > & | dvout | ||
) |
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1.
This function corresponds to the log map of the joint configuration Lie Group. Its output can be interpreted as a difference from the joint configuration space to the Lie algebra .
[in] | model | Model of the system on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Desired configuration (size model.nq) |
[out] | dvout | The corresponding velocity (size model.nv). |
Definition at line 142 of file joint-configuration.hpp.
void pinocchio::dIntegrate | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< Config_t > & | q, | ||
const Eigen::MatrixBase< Tangent_t > & | v, | ||
const Eigen::MatrixBase< JacobianOut_t > & | J, | ||
const ArgumentPosition | arg, | ||
const AssignmentOperatorType | op = SETTO |
||
) |
void pinocchio::dIntegrate | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< Config_t > & | q, | ||
const Eigen::MatrixBase< Tangent_t > & | v, | ||
const Eigen::MatrixBase< JacobianIn_t > & | J_in, | ||
int | self, | ||
const Eigen::MatrixBase< JacobianOut_t > & | J_out, | ||
const ArgumentPosition | arg, | ||
const AssignmentOperatorType | op = SETTO |
||
) |
void pinocchio::dIntegrate | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< Config_t > & | q, | ||
const Eigen::MatrixBase< Tangent_t > & | v, | ||
int | self, | ||
const Eigen::MatrixBase< JacobianIn_t > & | J_in, | ||
const Eigen::MatrixBase< JacobianOut_t > & | J_out, | ||
const ArgumentPosition | arg, | ||
const AssignmentOperatorType | op = SETTO |
||
) |
void pinocchio::dIntegrate | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType > & | J, | ||
const ArgumentPosition | arg, | ||
const AssignmentOperatorType | op | ||
) |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into the tangent space at identity.
This jacobian has to be interpreted in terms of Lie group, not vector space: as such, it is expressed in the tangent space only, not the configuration space. Calling the integrate function, these jacobians satisfy the following relationships in the tangent space:
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | J | Jacobian of the Integrate operation, either with respect to q or v (size model.nv x model.nv). |
[in] | arg | Argument (either q or v) with respect to which the differentiation is performed. |
This jacobian has to be interpreted in terms of Lie group, not vector space: as such, it is expressed in the tangent space only, not the configuration space. Calling the integrate function, these jacobians satisfy the following relationships in the tangent space:
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | J | Jacobian of the Integrate operation, either with respect to q or v (size model.nv x model.nv). |
[in] | arg | Argument (either q or v) with respect to which the differentiation is performed. |
Definition at line 337 of file joint-configuration.hpp.
void pinocchio::dIntegrate | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType > & | J, | ||
const ArgumentPosition | arg | ||
) |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into the tangent space at identity.
This jacobian has to be interpreted in terms of Lie group, not vector space: as such, it is expressed in the tangent space only, not the configuration space. Calling the integrate function, these jacobians satisfy the following relationships in the tangent space:
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | J | Jacobian of the Integrate operation, either with respect to q or v (size model.nv x model.nv). |
[in] | arg | Argument (either q or v) with respect to which the differentiation is performed. |
Definition at line 308 of file joint-configuration.hpp.
void pinocchio::dIntegrate | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType > & | J, | ||
const ArgumentPosition | arg, | ||
const AssignmentOperatorType | op | ||
) |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into the tangent space at identity.
This jacobian has to be interpreted in terms of Lie group, not vector space: as such, it is expressed in the tangent space only, not the configuration space. Calling the integrate function, these jacobians satisfy the following relationships in the tangent space:
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | J | Jacobian of the Integrate operation, either with respect to q or v (size model.nv x model.nv). |
[in] | arg | Argument (either q or v) with respect to which the differentiation is performed. |
Definition at line 337 of file joint-configuration.hpp.
void pinocchio::dIntegrateTransport | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< Config_t > & | q, | ||
const Eigen::MatrixBase< Tangent_t > & | v, | ||
const Eigen::MatrixBase< JacobianIn_t > & | J_in, | ||
const Eigen::MatrixBase< JacobianOut_t > & | J_out, | ||
const ArgumentPosition | arg | ||
) |
void pinocchio::dIntegrateTransport | ( | const LieGroupGenericTpl< LieGroupCollection > & | lg, |
const Eigen::MatrixBase< Config_t > & | q, | ||
const Eigen::MatrixBase< Tangent_t > & | v, | ||
const Eigen::MatrixBase< JacobianOut_t > & | J, | ||
const ArgumentPosition | arg | ||
) |
void pinocchio::dIntegrateTransport | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType1 > & | Jin, | ||
const Eigen::MatrixBase< JacobianMatrixType2 > & | Jout, | ||
const ArgumentPosition | arg | ||
) |
Transport a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element , to the tangent space at . It performs the product with the Jacobian of integrate by exploiting at best the sparsity of the underlying operations. In other words, this functions transforms a tangent vector expressed at to a tangent vector expressed at , considering that the change of configuration between and may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation on a spatial velocity . In the context of configuration spaces assimilated as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | Jin | Input matrix (number of rows = model.nv). |
[out] | Jout | Output matrix (same size as Jin). |
[in] | arg | Argument (either ARG0 for q or ARG1 for v) with respect to which the differentation is performed. |
Definition at line 398 of file joint-configuration.hpp.
void pinocchio::dIntegrateTransport | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType1 > & | Jin, | ||
const Eigen::MatrixBase< JacobianMatrixType2 > & | Jout, | ||
const ArgumentPosition | arg | ||
) |
Transport a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element , to the tangent space at . It performs the product with the Jacobian of integrate by exploiting at best the sparsity of the underlying operations. In other words, this functions transforms a tangent vector expressed at to a tangent vector expressed at , considering that the change of configuration between and may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation on a spatial velocity . In the context of configuration spaces assimilated as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | Jin | Input matrix (number of rows = model.nv). |
[out] | Jout | Output matrix (same size as Jin). |
[in] | arg | Argument (either ARG0 for q or ARG1 for v) with respect to which the differentation is performed. |
Definition at line 398 of file joint-configuration.hpp.
void pinocchio::dIntegrateTransport | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType > & | J, | ||
const ArgumentPosition | arg | ||
) |
Transport in place a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element , to the tangent space at . In other words, this functions transforms a tangent vector expressed at to a tangent vector expressed at , considering that the change of configuration between and may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation on a spatial velocity . In the context of configuration spaces assimilated as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[in,out] | J | Input/output matrix (number of rows = model.nv). |
[in] | arg | Argument (either ARG0 for q or ARG1 for v) with respect to which the differentation is performed. |
Definition at line 454 of file joint-configuration.hpp.
void pinocchio::dIntegrateTransport | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< JacobianMatrixType > & | J, | ||
const ArgumentPosition | arg | ||
) |
Transport in place a matrix from the terminal to the originate tangent space of the integrate operation, with respect to the configuration or the velocity arguments.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element , to the tangent space at . In other words, this functions transforms a tangent vector expressed at to a tangent vector expressed at , considering that the change of configuration between and may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation on a spatial velocity . In the context of configuration spaces assimilated as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[in,out] | J | Input/output matrix (number of rows = model.nv). |
[in] | arg | Argument (either ARG0 for q or ARG1 for v) with respect to which the differentation is performed. |
Definition at line 454 of file joint-configuration.hpp.
|
inline |
Visit a JointDataTpl through JointDInvInertiaVisitor to get the D^{-1} matrix of the inertia matrix decomposition.
[in] | jdata | The jdata |
|
inline |
Definition at line 97 of file liegroup-variant-visitors.hpp.
|
inline |
Distance between two configuration vectors, namely .
[in] | model | Model we want to compute the distance |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
Distance between two configuration vectors, namely .
[in] | model | Model we want to compute the distance |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
Definition at line 581 of file joint-configuration.hpp.
|
inline |
Distance between two configuration vectors.
Distance between two configuration vectors, namely .
[in] | model | Model we want to compute the distance |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
Definition at line 581 of file joint-configuration.hpp.
|
inline |
Definition at line 117 of file timings.cpp.
|
inline |
Definition at line 151 of file timings.cpp.
|
inline |
Definition at line 49 of file timings.cpp.
|
inline |
Definition at line 81 of file timings.cpp.
Eigen::Matrix<typename Vector3Like::Scalar,3,3,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::exp3 | ( | const Eigen::MatrixBase< Vector3Like > & | v | ) |
Exp: so3 -> SO3.
Return the integral of the input angular velocity during time 1.
[in] | v | The angular velocity vector. |
Definition at line 34 of file src/spatial/explog.hpp.
SE3Tpl<typename MotionDerived::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options> pinocchio::exp6 | ( | const MotionDense< MotionDerived > & | nu | ) |
Exp: se3 -> SE3.
Return the integral of the input twist during time 1.
[in] | nu | The input twist. |
Definition at line 326 of file src/spatial/explog.hpp.
SE3Tpl<typename Vector6Like::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options> pinocchio::exp6 | ( | const Eigen::MatrixBase< Vector6Like > & | v | ) |
Exp: se3 -> SE3.
Return the integral of the input spatial velocity during time 1.
[in] | v | The twist represented by a vector. |
Definition at line 385 of file src/spatial/explog.hpp.
PINOCCHIO_DLLAPI void pinocchio::extractPathFromEnvVar | ( | const std::string & | env_var_name, |
std::vector< std::string > & | list_of_paths, | ||
const std::string & | delimiter = ":" |
||
) |
Parse an environment variable if exists and extract paths according to the delimiter.
[in] | env_var_name | The name of the environment variable. |
[out] | list_of_paths | List of path to fill with the paths extracted from the environment variable value. |
[in] | delimiter | The delimiter between two consecutive paths. |
Definition at line 13 of file file-explorer.cpp.
PINOCCHIO_DLLAPI std::vector< std::string > pinocchio::extractPathFromEnvVar | ( | const std::string & | env_var_name, |
const std::string & | delimiter = ":" |
||
) |
Parse an environment variable if exists and extract paths according to the delimiter.
[in] | env_var_name | The name of the environment variable. |
[in] | delimiter | The delimiter between two consecutive paths. |
Definition at line 38 of file file-explorer.cpp.
|
inline |
Compute the forward dynamics with contact constraints. Internally, pinocchio::computeAllTerms is called.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
ConstraintMatrixType | Type of the constraint matrix. |
DriftVectorType | Type of the drift vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v | The joint velocity (vector dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[in] | J | The Jacobian of the constraints (dim nb_constraints*model.nv). |
[in] | gamma | The drift of the constraints (dim nb_constraints). |
[in] | inv_damping | Damping factor for Cholesky decomposition of JMinvJt. Set to zero if constraints are full rank. |
|
inline |
Compute the forward dynamics with contact constraints, assuming pinocchio::computeAllTerms has been called.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
ConstraintMatrixType | Type of the constraint matrix. |
DriftVectorType | Type of the drift vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | v | The joint velocity (vector dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[in] | J | The Jacobian of the constraints (dim nb_constraints*model.nv). |
[in] | gamma | The drift of the constraints (dim nb_constraints). |
[in] | inv_damping | Damping factor for Cholesky decomposition of JMinvJt. Set to zero if constraints are full rank. |
|
inline |
Compute the forward dynamics with contact constraints.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint torque vector. |
ConstraintMatrixType | Type of the constraint matrix. |
DriftVectorType | Type of the drift vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v | The joint velocity (vector dim model.nv). |
[in] | tau | The joint torque vector (dim model.nv). |
[in] | J | The Jacobian of the constraints (dim nb_constraints*model.nv). |
[in] | gamma | The drift of the constraints (dim nb_constraints). |
[in] | inv_damping | Damping factor for Cholesky decomposition of JMinvJt. Set to zero if constraints are full rank. |
[in] | updateKinematics | If true, the algorithm calls first pinocchio::computeAllTerms. Otherwise, it uses the current dynamic values stored in data. \ % |
Definition at line 130 of file contact-dynamics.hpp.
|
inline |
Update the joint placements according to the current joint configuration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
|
inline |
Update the joint placements and spatial velocities according to the current joint configuration and velocity.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v | The joint velocity (vector dim model.nv). |
|
inline |
Update the joint placements, spatial velocities and spatial accelerations according to the current joint configuration, velocity and acceleration.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v | The joint velocity (vector dim model.nv). |
[in] | a | The joint acceleration (vector dim model.nv). |
|
inline |
Computes the regressor for the dynamic parameters of a rigid body attached to a given frame, puts the result in data.bodyRegressor and returns it.
This algorithm assumes RNEA has been run to compute the acceleration and gravitational effects.
The result is such that where is the net force acting on the body, including gravity
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | frameId | The id of the frame. |
|
inline |
This function is now deprecated and has been renamed computeFrameJacobian. This signature will be removed in future release of Pinocchio.
Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | frameId | The id of the Frame refering to model.frames[frameId]. |
[in] | reference_frame | Reference frame in which the Jacobian is expressed. |
[out] | J | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill J with zero elements, e.g. J.setZero(). |
Definition at line 235 of file frames.hpp.
|
inline |
First calls the forwardKinematics on the model, then computes the placement of each frame. /sa pinocchio::forwardKinematics.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The kinematic model. |
data | Data associated to model. | |
[in] | q | Configuration vector. |
|
inline |
Updates the position of each frame contained in the model. This function is now deprecated and has been renamed updateFramePlacements.
JointCollection | Collection of Joint types. |
[in] | model | The kinematic model. |
data | Data associated to model. |
Definition at line 76 of file frames.hpp.
|
inline |
Returns the spatial acceleration of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | jointId | Id of the joint |
[in] | rf | Reference frame in which the acceleration is expressed. |
|
inline |
Computes the partial derivatie of the center-of-mass velocity with respect to the joint configuration q. You must first call computeAllTerms(model,data,q,v) or computeCenterOfMass(model,data,q,v) before calling this function.
JointCollection | Collection of Joint types. |
Matrix3xOut | Matrix3x containing the partial derivatives of the CoM velocity with respect to the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[out] | v_partial_dq | Partial derivative of the CoM velocity w.r.t. . |
|
inline |
Retrive the analytical derivatives of the centroidal dynamics from the RNEA derivatives. pinocchio::computeRNEADerivatives should have been called first.
Computes the first order approximation of the centroidal dynamics time derivative and corresponds to the following equation
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[out] | dhdot_dq | The partial derivative of the centroidal dynamics with respect to the configuration vector (dim 6 x model.nv). |
[out] | dhdot_dv | The partial derivative of the centroidal dynamics with respect to the velocity vector (dim 6 x model.nv). |
[out] | dhdot_da | The partial derivative of the centroidal dynamics with respect to the acceleration vector (dim 6 x model.nv). |
|
inline |
Returns the "classical" acceleration of the joint expressed in the desired reference frame. This is different from the "spatial" acceleration in that centrifugal effects are accounted for. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | jointId | Id of the joint |
[in] | rf | Reference frame in which the acceleration is expressed. |
|
inline |
Extracts the center of mass position from the joint space inertia matrix (also called the mass matrix).
JointCollection | Collection of Joint types. |
Matrix3xLike | Type of the output Jacobian matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Retrives the Coriolis Matrix of the Lagrangian dynamics:
after a call to the dynamics derivatives.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Returns the spatial acceleration of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the acceleration is expressed. |
void pinocchio::getFrameAccelerationDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xOut1 > & | v_partial_dq, | ||
const Eigen::MatrixBase< Matrix6xOut2 > & | a_partial_dq, | ||
const Eigen::MatrixBase< Matrix6xOut3 > & | a_partial_dv, | ||
const Eigen::MatrixBase< Matrix6xOut4 > & | a_partial_da | ||
) |
Computes the partial derivatives of the frame acceleration quantity with respect to q, v and a. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da.
JointCollection | Collection of Joint types. |
Matrix6xOut1 | Matrix6x containing the partial derivatives of the frame spatial velocity with respect to the joint configuration vector. |
Matrix6xOut2 | Matrix6x containing the partial derivatives of the frame spatial acceleration with respect to the joint configuration vector. |
Matrix6xOut3 | Matrix6x containing the partial derivatives of the frame spatial acceleration with respect to the joint velocity vector. |
Matrix6xOut4 | Matrix6x containing the partial derivatives of the frame spatial acceleration with respect to the joint acceleration vector. |
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the velocity is expressed. |
[out] | v_partial_dq | Partial derivative of the joint spatial velocity w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
void pinocchio::getFrameAccelerationDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xOut1 > & | v_partial_dq, | ||
const Eigen::MatrixBase< Matrix6xOut2 > & | v_partial_dv, | ||
const Eigen::MatrixBase< Matrix6xOut3 > & | a_partial_dq, | ||
const Eigen::MatrixBase< Matrix6xOut4 > & | a_partial_dv, | ||
const Eigen::MatrixBase< Matrix6xOut5 > & | a_partial_da | ||
) |
Computes the partial derivatives of the frame acceleration quantity with respect to q, v and a. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da.
JointCollection | Collection of Joint types. |
Matrix6xOut1 | Matrix6x containing the partial derivatives of the frame spatial velocity with respect to the joint configuration vector. |
Matrix6xOut2 | Matrix6x containing the partial derivatives of the frame spatial velocity with respect to the joint velocity vector. |
Matrix6xOut3 | Matrix6x containing the partial derivatives of the frame spatial acceleration with respect to the joint configuration vector. |
Matrix6xOut4 | Matrix6x containing the partial derivatives of the frame spatial acceleration with respect to the joint velocity vector. |
Matrix6xOut5 | Matrix6x containing the partial derivatives of the frame spatial acceleration with respect to the joint acceleration vector. |
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the velocity is expressed. |
[out] | v_partial_dq | Partial derivative of the joint spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the joint spatial velociy w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
|
inline |
Returns the "classical" acceleration of the Frame expressed in the desired reference frame. This is different from the "spatial" acceleration in that centrifugal effects are accounted for. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the acceleration is expressed. |
|
inline |
Returns the jacobian of the frame expressed either expressed in the LOCAL frame coordinate system or in the WORLD coordinate system, depending on the value of rf. You must first call pinocchio::computeJointJacobians followed by pinocchio::framesForwardKinematics to update placement values in data structure.
JointCollection | Collection of Joint types. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the Jacobian is expressed. |
[out] | J | The Jacobian of the Frame expressed in the coordinates Frame. |
void pinocchio::getFrameJacobianTimeVariation | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xLike > & | dJ | ||
) |
Computes the Jacobian time variation of a specific frame (given by frame_id) expressed either in the LOCAL frame.
JointCollection | Collection of Joint types. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | frameId | The index of the frame. |
[out] | dJ | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill dJ with zero elements, e.g. dJ.fill(0.). |
|
inline |
Returns the spatial velocity of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure.
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the velocity is expressed. |
void pinocchio::getFrameVelocityDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xOut1 > & | v_partial_dq, | ||
const Eigen::MatrixBase< Matrix6xOut2 > & | v_partial_dv | ||
) |
Computes the partial derivatives of the frame velocity quantity with respect to q and v. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities.
JointCollection | Collection of Joint types. |
Matrix6xOut1 | Matrix6x containing the partial derivatives of the frame spatial velocity with respect to the joint configuration vector. |
Matrix6xOut2 | Matrix6x containing the partial derivatives of the frame spatial velocity with respect to the joint velocity vector. |
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Id of the operational Frame |
[in] | rf | Reference frame in which the velocity is expressed. |
[out] | v_partial_dq | Partial derivative of the joint spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the joint spatial velociy w.r.t. . |
|
inline |
Extracts both the jacobian of the center of mass (CoM), the total mass of the system and the CoM position from the joint space inertia matrix (also called the mass matrix). The results are accessible through data.Jcom, data.mass[0] and data.com[0] and are both expressed in the world frame.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
|
inline |
Retrieves the Jacobian of the center of mass of the given subtree according to the current value stored in data. It assumes that pinocchio::jacobianCenterOfMass has been called first with computeSubtreeComs equals to true.
JointCollection | Collection of Joint types. |
Matrix3xLike | Type of the output Jacobian matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | rootSubtreeId | Index of the parent joint supporting the subtree. |
[out] | res | The Jacobian matrix where the results will be stored in (dim 3 x model.nv). You must first fill J with zero elements, e.g. J.setZero(). |
|
inline |
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint configuration, velocity and acceleration. You must first call computForwardKinematicsDerivatives before calling this function. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da.
JointCollection | Collection of Joint types. |
Matrix6xOut1 | Matrix6x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector. |
Matrix6xOut2 | Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint configuration vector. |
Matrix6xOut3 | Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint velocity vector. |
Matrix6xOut4 | Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | jointId | Index of the joint in model. |
[in] | rf | Reference frame in which the Jacobian is expressed. |
[out] | v_partial_dq | Partial derivative of the joint spatial velocity w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
|
inline |
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint configuration, velocity and acceleration. You must first call computForwardKinematicsDerivatives before calling this function. It is important to notice that a direct outcome (for free) of this algo is v_partial_dq and v_partial_dv which is equal to a_partial_da.
JointCollection | Collection of Joint types. |
Matrix6xOut1 | Matrix6x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector. |
Matrix6xOut2 | Matrix6x containing the partial derivatives of the spatial velocity with respect to the joint velocity vector. |
Matrix6xOut3 | Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint configuration vector. |
Matrix6xOut4 | Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint velocity vector. |
Matrix6xOut5 | Matrix6x containing the partial derivatives of the spatial acceleration with respect to the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | jointId | Index of the joint in model. |
[in] | rf | Reference frame in which the Jacobian is expressed. |
[out] | v_partial_dq | Partial derivative of the joint spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the joint spatial velociy w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the joint spatial acceleration w.r.t. . |
|
inline |
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.
For the world frame W, the Jacobian j$ to the world frame $0$ is such that {}^0 v_{0j}$ is the spatial velocity of the joint frame. (When serialized to a 6D vector, the three linear coordinates are followed by the three angular coordinates).
JointCollection | Collection of Joint types. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | localFrame | Expressed the Jacobian in the local frame or world frame coordinates system. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | jointId | The id of the joint. |
[out] | J | A reference to the Jacobian matrix where the results will be stored (dim 6 x model.nv). You must fill J with zero elements, e.g. J.fill(0.). |
|
inline |
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.
JointCollection | Collection of Joint types. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | localFrame | Expressed the Jacobian in the local frame or world frame coordinates system. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | jointId | The id of the joint. |
[out] | dJ | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill dJ with zero elements, e.g. dJ.fill(0.). |
|
inline |
Retrieves the kinematic Hessian of a given joint according to the values aleardy computed by computeJointKinematicHessians and stored in data. While the kinematic Jacobian of a given joint frame corresponds to the first order derivative of the placement variation with respect to , the kinematic Hessian corresponds to the second order derivation of placement variation, which in turns also corresponds to the first order derivative of the kinematic Jacobian. The frame in which the kinematic Hessian is precised by the input argument rf.
Scalar | Scalar type of the kinematic model. |
Options | Alignement options of the kinematic model. |
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | Index of the joint in model. |
[in] | rf | Reference frame with respect to which the derivative of the Jacobian is expressed |
[out] | kinematic_hessian | Second order derivative of the joint placement w.r.t. expressed in the frame given by rf. |
|
inline |
Retrieves the kinematic Hessian of a given joint according to the values aleardy computed by computeJointKinematicHessians and stored in data. While the kinematic Jacobian of a given joint frame corresponds to the first order derivative of the placement variation with respect to , the kinematic Hessian corresponds to the second order derivation of placement variation, which in turns also corresponds to the first order derivative of the kinematic Jacobian.
Scalar | Scalar type of the kinematic model. |
Options | Alignement options of the kinematic model. |
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | Index of the joint in model. |
[in] | rf | Reference frame with respect to which the derivative of the Jacobian is expressed. |
Definition at line 223 of file kinematics-derivatives.hpp.
|
inline |
Computes the partial derivaties of the spatial velocity of a given with respect to the joint configuration and velocity. You must first call computForwardKinematicsDerivatives before calling this function.
JointCollection | Collection of Joint types. |
Matrix6xOut1 | Matrix6x containing the partial derivatives with respect to the joint configuration vector. |
Matrix6xOut2 | Matrix6x containing the partial derivatives with respect to the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | rf | Reference frame in which the Jacobian is expressed. |
[out] | v_partial_dq | Partial derivative of the joint velociy w.r.t. . |
[out] | v_partial_dv | Partial derivative of the joint velociy w.r.t. . |
|
inline |
Computes the inverse of the KKT matrix for dynamics with contact constraints. It computes the following matrix:
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | J | Jacobian of the constraints. |
[out] | KKTMatrix_inv | inverse of the MJtJ matrix. |
|
inline |
Returns the number of thread defined by the environment variable OMP_NUM_THREADS. If this variable is not defined, this simply returns the default value 1.
Definition at line 16 of file openmp.hpp.
|
inline |
Returns the spatial velocity of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure.
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | jointId | Id of the joint |
[in] | rf | Reference frame in which the velocity is expressed. |
|
inline |
Visit a JointModelTpl through JointConfigurationLimitVisitor to get the configurations limits.
[in] | jmodel | The JointModelVariant |
|
inline |
Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limits in tangent space.
[in] | jmodel | The JointModelVariant |
|
inline |
Definition at line 18 of file math/matrix.hpp.
bool pinocchio::hasSameIndexes | ( | const JointModelTpl< Scalar, Options, JointCollectionTpl > & | jmodel_generic, |
const JointModelBase< JointModelDerived > & | jmodel | ||
) |
Check whether JointModelTpl<Scalar,...> has the indexes than another JointModelDerived.
[in] | jmodel_generic | The generic joint model containing a variant. |
[in] | jmodel | The other joint modelto compare with |
void pinocchio::Hlog3 | ( | const Scalar & | theta, |
const Eigen::MatrixBase< Vector3Like1 > & | log, | ||
const Eigen::MatrixBase< Vector3Like2 > & | v, | ||
const Eigen::MatrixBase< Matrix3Like > & | vt_Hlog | ||
) |
Definition at line 256 of file src/spatial/explog.hpp.
void pinocchio::Hlog3 | ( | const Eigen::MatrixBase< Matrix3Like1 > & | R, |
const Eigen::MatrixBase< Vector3Like > & | v, | ||
const Eigen::MatrixBase< Matrix3Like2 > & | vt_Hlog | ||
) |
Second order derivative of log3.
This computes .
[in] | R | the rotation matrix. |
[in] | v | the 3D vector. |
[out] | vt_Hlog | the product of the Hessian with the input vector |
Definition at line 303 of file src/spatial/explog.hpp.
|
inline |
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain.
[in] | jmodel | The JointModelVariant |
|
inline |
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space corresponding to the first degree of freedom of the Joint.
[in] | jmodel | The JointModelVariant |
|
inline |
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corresponding to the first joint tangent space degree.
[in] | jmodel | The JointModelVariant |
|
inline |
Compute the impulse dynamics with contact constraints. Internally, pinocchio::crba is called.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
ConstraintMatrixType | Type of the constraint matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v_before | The joint velocity before impact (vector dim model.nv). |
[in] | J | The Jacobian of the constraints (dim nb_constraints*model.nv). |
[in] | r_coeff | The coefficient of restitution. Must be in [0;1]. |
[in] | inv_damping | Damping factor for Cholesky decomposition of JMinvJt. Set to zero if constraints are full rank. |
|
inline |
Compute the impulse dynamics with contact constraints, assuming pinocchio::crba has been called.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
ConstraintMatrixType | Type of the constraint matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | v_before | The joint velocity before impact (vector dim model.nv). |
[in] | J | The Jacobian of the constraints (dim nb_constraints*model.nv). |
[in] | r_coeff | The coefficient of restitution. Must be in [0;1]. |
[in] | inv_damping | Damping factor for Cholesky decomposition of JMinvJt. Set to zero if constraints are full rank. |
|
inline |
Compute the impulse dynamics with contact constraints.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
ConstraintMatrixType | Type of the constraint matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration (vector dim model.nq). |
[in] | v_before | The joint velocity before impact (vector dim model.nv). |
[in] | J | The Jacobian of the constraints (dim nb_constraints*model.nv). |
[in] | r_coeff | The coefficient of restitution. Must be in [0;1]. |
[in] | updateKinematics | If true, the algorithm calls first pinocchio::crba. Otherwise, it uses the current mass matrix value stored in data. |
Definition at line 282 of file contact-dynamics.hpp.
void pinocchio::integrate | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
This function corresponds to the exponential map of the joint configuration Lie Group. Its output can be interpreted as the "sum" from the Lie algebra to the joint configuration space .
[in] | model | Model of the kinematic tree on which the integration is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | qout | The integrated configuration (size model.nq) |
Definition at line 54 of file joint-configuration.hpp.
void pinocchio::integrate | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v, | ||
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
This function corresponds to the exponential map of the joint configuration Lie Group. Its output can be interpreted as the "sum" from the Lie algebra to the joint configuration space .
[in] | model | Model of the kinematic tree on which the integration is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
[out] | qout | The integrated configuration (size model.nq) |
Definition at line 54 of file joint-configuration.hpp.
|
inline |
Visit a LieGroupVariant to call its integrate method.
[in] | lg | the LieGroupVariant. |
[in] | q | the starting configuration. |
[in] | v | the tangent velocity. |
|
inline |
Return the Jacobian of the integrate function for the components of the config vector.
[in] | model | Model of the kinematic tree. |
[out] | jacobian | The Jacobian of the integrate operation. |
This function is often required for the numerical solvers that are working on the tangent of the configuration space, instead of the configuration space itself.
Definition at line 721 of file joint-configuration.hpp.
|
inline |
Return the Jacobian of the integrate function for the components of the config vector.
[in] | model | Model of the kinematic tree. |
[out] | jacobian | The Jacobian of the integrate operation. |
This function is often required for the numerical solvers that are working on the tangent of the configuration space, instead of the configuration space itself.
Definition at line 721 of file joint-configuration.hpp.
void pinocchio::interpolate | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1, | ||
const Scalar & | u, | ||
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Interpolate two configurations for a given model.
[in] | model | Model of the kinematic tree on which the interpolation is performed. |
[in] | q0 | Initial configuration vector (size model.nq) |
[in] | q1 | Final configuration vector (size model.nq) |
[in] | u | u in [0;1] position along the interpolation. |
[out] | qout | The interpolated configuration (q0 if u = 0, q1 if u = 1) |
Definition at line 96 of file joint-configuration.hpp.
|
inline |
|
inline |
Definition at line 213 of file math/matrix.hpp.
bool pinocchio::isEqual | ( | const JointModelTpl< Scalar, Options, JointCollectionTpl > & | jmodel_generic, |
const JointModelBase< JointModelDerived > & | jmodel | ||
) |
Visit a JointModelTpl<Scalar,...> to compare it to JointModelDerived.
[in] | jmodel_generic | The generic joint model containing a variant. |
[in] | jmodel | The other joint model for the comparison. |
bool pinocchio::isEqual | ( | const JointDataTpl< Scalar, Options, JointCollectionTpl > & | jmodel_generic, |
const JointDataBase< JointDataDerived > & | jmodel | ||
) |
Visit a JointDataTpl<Scalar,...> to compare it to another JointData.
[in] | jdata_generic | The generic joint data containing a variant. |
[in] | jdata | The other joint data for the comparison. |
|
inline |
|
inline |
Check whether the input vector is Normalized within the given precision.
[in] | vec | Input vector |
[in] | prec | Required precision |
Definition at line 188 of file math/matrix.hpp.
|
inline |
Check whether a configuration vector is normalized within the given precision provided by prec.
[in] | model | Model of the kinematic tree. |
[in] | q | Configuration to check (size model.nq). |
[in] | prec | Precision. |
Definition at line 641 of file joint-configuration.hpp.
|
inline |
Check whether a configuration vector is normalized within the given precision provided by prec.
[in] | model | Model of the kinematic tree. |
[in] | q | Configuration to check (size model.nq). |
[in] | prec | Precision. |
Definition at line 641 of file joint-configuration.hpp.
|
inline |
|
inline |
Return true if the given configurations are equivalents, within the given precision.
[in] | model | Model of the kinematic tree. |
[in] | q1 | The first configuraiton to compare. |
[in] | q2 | The second configuration to compare. |
[in] | prec | precision of the comparison. |
[in] | model | Model of the kinematic tree. |
[in] | q1 | The first configuraiton to compare |
[in] | q2 | The second configuration to compare |
[in] | prec | precision of the comparison. |
Definition at line 683 of file joint-configuration.hpp.
|
inline |
Return true if the given configurations are equivalents, within the given precision.
[in] | model | Model of the kinematic tree. |
[in] | q1 | The first configuraiton to compare |
[in] | q2 | The second configuration to compare |
[in] | prec | precision of the comparison. |
Definition at line 683 of file joint-configuration.hpp.
|
inline |
Check whether the input matrix is Unitary within the given precision.
[in] | mat | Input matrix |
[in] | prec | Required precision |
Definition at line 140 of file math/matrix.hpp.
|
inline |
Definition at line 56 of file math/matrix.hpp.
|
inline |
Computes both the jacobian and the the center of mass position of a given model according to a particular joint configuration. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | computeSubtreeComs | If true, the algorithm also computes the centers of mass of the subtrees, expressed in the world coordinate frame. |
|
inline |
Computes both the jacobian and the the center of mass position of a given model according to the current value stored in data. It assumes that forwardKinematics has been called first. The results are accessible through data.Jcom and data.com[0] and are both expressed in the world frame. In addition, the algorithm also computes the Jacobian of all the joints (.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | computeSubtreeComs | If true, the algorithm also computes the center of mass of the subtrees, expressed in the world coordinate frame. |
|
inline |
Computes the Jacobian of the center of mass of the given subtree according to a particular joint configuration. In addition, the algorithm also computes the Jacobian of all the joints (.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
Matrix3xLike | Type of the output Jacobian matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | rootSubtreeId | Index of the parent joint supporting the subtree. |
[out] | res | The Jacobian matrix where the results will be stored in (dim 3 x model.nv). You must first fill J with zero elements, e.g. J.setZero(). |
|
inline |
Computes the Jacobian of the center of mass of the given subtree according to the current value stored in data. It assumes that forwardKinematics has been called first.
JointCollection | Collection of Joint types. |
Matrix3xLike | Type of the output Jacobian matrix. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | rootSubtreeId | Index of the parent joint supporting the subtree. |
[out] | res | The Jacobian matrix where the results will be stored in (dim 3 x model.nv). You must first fill J with zero elements, e.g. J.setZero(). |
void pinocchio::Jexp3 | ( | const Eigen::MatrixBase< Vector3Like > & | r, |
const Eigen::MatrixBase< Matrix3Like > & | Jexp | ||
) |
void pinocchio::Jexp3 | ( | const Eigen::MatrixBase< Vector3Like > & | r, |
const Eigen::MatrixBase< Matrix3Like > & | Jexp | ||
) |
void pinocchio::Jexp6 | ( | const MotionDense< MotionDerived > & | nu, |
const Eigen::MatrixBase< Matrix6Like > & | Jexp | ||
) |
Derivative of exp6 Computed as the inverse of Jlog6.
Definition at line 439 of file src/spatial/explog.hpp.
void pinocchio::Jexp6 | ( | const MotionDense< MotionDerived > & | nu, |
const Eigen::MatrixBase< Matrix6Like > & | Jexp | ||
) |
Derivative of exp6 Computed as the inverse of Jlog6.
Definition at line 529 of file src/spatial/explog.hpp.
void pinocchio::Jlog3 | ( | const Scalar & | theta, |
const Eigen::MatrixBase< Vector3Like > & | log, | ||
const Eigen::MatrixBase< Matrix3Like > & | Jlog | ||
) |
Derivative of log3.
This function is the right derivative of log3, that is, for and , it provides the linear approximation:
[in] | theta | the angle value. |
[in] | log | the output of log3. |
[out] | Jlog | the jacobian |
Equivalently, is the right Jacobian of :
Note that this is the right Jacobian: . (By convention, calculations in Pinocchio always perform right differentiation, i.e., Jacobians are in local coordinates (also known as body coordinates), unless otherwise specified.)
If we denote by and , then can be calculated as:
where denotes the skew-symmetric matrix obtained from the 3D vector .
Definition at line 223 of file src/spatial/explog.hpp.
void pinocchio::Jlog3 | ( | const Eigen::MatrixBase< Matrix3Like1 > & | R, |
const Eigen::MatrixBase< Matrix3Like2 > & | Jlog | ||
) |
Derivative of log3.
[in] | R | the rotation matrix. |
[out] | Jlog | the jacobian |
Equivalent to
Definition at line 244 of file src/spatial/explog.hpp.
void pinocchio::Jlog6 | ( | const SE3Tpl< Scalar, Options > & | M, |
const Eigen::MatrixBase< Matrix6Like > & | Jlog | ||
) |
Derivative of log6.
This function is the right derivative of log6, that is, for and , it provides the linear approximation:
Equivalently, is the right Jacobian of :
Note that this is the right Jacobian: . (By convention, calculations in Pinocchio always perform right differentiation, i.e., Jacobians are in local coordinates (also known as body coordinates), unless otherwise specified.)
Internally, it is calculated using the following formulas:
where
and
For , let and . Then, we have the following partial (right) Jacobians:
Let , and . Then, we have the following partial (right) Jacobian:
Definition at line 594 of file src/spatial/explog.hpp.
|
inline |
Visit a JointDataTpl through JointTransformVisitor to get the joint internal transform (transform between the entry frame and the exit frame of the joint).
[in] | jdata | The joint data to visit. |
|
inline |
Computes the regressor for the dynamic parameters of a rigid body attached to a given joint, puts the result in data.bodyRegressor and returns it.
This algorithm assumes RNEA has been run to compute the acceleration and gravitational effects.
The result is such that where is the net force acting on the body, including gravity
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | jointId | The id of the joint. |
|
inline |
This function is now deprecated and has been renamed into computeJointJacobian. It will be removed in future releases of Pinocchio.
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.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
Matrix6xLike | Type of the matrix containing the joint Jacobian. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | jointId | The id of the joint refering to model.joints[jointId]. |
[out] | J | A reference on the Jacobian matrix where the results will be stored in (dim 6 x model.nv). You must fill J with zero elements, e.g. J.setZero(). |
Definition at line 112 of file jacobian.hpp.
|
inline |
Computes the kinetic energy of the system. The result is accessible through data.kinetic_energy.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | update_kinematics | If true, first apply the forward kinematics on the kinematic tree. |
Definition at line 76 of file energy.hpp.
Eigen::Matrix<typename Matrix3Like::Scalar,3,1,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::log3 | ( | const Eigen::MatrixBase< Matrix3Like > & | R, |
typename Matrix3Like::Scalar & | theta | ||
) |
Same as log3.
[in] | R | the rotation matrix. |
[out] | theta | the angle value. |
Definition at line 75 of file src/spatial/explog.hpp.
Eigen::Matrix<typename Matrix3Like::Scalar,3,1,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::log3 | ( | const Eigen::MatrixBase< Matrix3Like > & | R | ) |
Log: SO(3)-> so(3).
Pseudo-inverse of log from .
[in] | R | The rotation matrix. |
Definition at line 96 of file src/spatial/explog.hpp.
MotionTpl<Scalar,Options> pinocchio::log6 | ( | const SE3Tpl< Scalar, Options > & | M | ) |
Log: SE3 -> se3.
Pseudo-inverse of exp from .
[in] | M | The rigid transformation. |
Definition at line 403 of file src/spatial/explog.hpp.
MotionTpl<typename Matrix4Like::Scalar,Eigen::internal::traits<Matrix4Like>::Options> pinocchio::log6 | ( | const Eigen::MatrixBase< Matrix4Like > & | M | ) |
Log: SE3 -> se3.
Pseudo-inverse of exp from .
[in] | M | The rigid transformation represented as an homogenous matrix. |
Definition at line 421 of file src/spatial/explog.hpp.
|
inline |
Default checker-list, used as the default argument in Model::check().
Definition at line 15 of file default-check.hpp.
|
inline |
Visit a JointDataTpl through JointMotionVisitor to get the joint internal motion as a dense motion.
[in] | jdata | The joint data to visit. |
|
inline |
Visit a LieGroupVariant to get the name of it.
[in] | lg | the LieGroupVariant. |
|
inline |
Visit a LieGroupVariant to get the neutral element of it.
[in] | lg | the LieGroupVariant. |
void pinocchio::neutral | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Return the neutral configuration element related to the model configuration space.
[in] | model | Model of the kinematic tree on which the neutral element is computed |
[out] | qout | The neutral configuration element (size model.nq). |
[in] | model | Model of the kinematic tree on which the neutral element is computed. |
[out] | qout | The neutral configuration element (size model.nq). |
Definition at line 257 of file joint-configuration.hpp.
void pinocchio::neutral | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Return the neutral configuration element related to the model configuration space.
[in] | model | Model of the kinematic tree on which the neutral element is computed. |
[out] | qout | The neutral configuration element (size model.nq). |
Definition at line 257 of file joint-configuration.hpp.
|
inline |
Return the neutral configuration element related to the model configuration space.
[in] | model | Model of the kinematic tree on which the neutral element is computed. |
Definition at line 991 of file joint-configuration.hpp.
|
inline |
Return the neutral configuration element related to the model configuration space.
[in] | model | Model of the kinematic tree on which the neutral element is computed. |
Definition at line 991 of file joint-configuration.hpp.
|
inline |
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects), also called the bias terms of the Lagrangian dynamics:
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType | Type of the joint velocity vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
|
inline |
|
inline |
Normalize a configuration vector.
[in] | model | Model of the kinematic tree. |
[in,out] | q | Configuration to normalize (size model.nq). |
Definition at line 609 of file joint-configuration.hpp.
|
inline |
Normalize a configuration vector.
[in] | model | Model of the kinematic tree. |
[in,out] | q | Configuration to normalize (size model.nq). |
Definition at line 609 of file joint-configuration.hpp.
void pinocchio::normalizeRotation | ( | const Eigen::MatrixBase< Matrix3 > & | rot | ) |
Orthogonormalization procedure for a rotation matrix (closed enough to SO(3)).
[in,out] | rot | A 3x3 matrix to orthonormalize |
Definition at line 59 of file rotation.hpp.
|
inline |
Visit a LieGroupVariant to get the dimension of the Lie group configuration space.
[in] | lg | the LieGroupVariant. |
|
inline |
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space.
[in] | jmodel | The JointModelVariant |
|
inline |
Visit a LieGroupVariant to get the dimension of the Lie group tangent space.
[in] | lg | the LieGroupVariant. |
|
inline |
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space.
[in] | jmodel | The JointModelVariant |
bool pinocchio::operator!= | ( | const JointDataBase< JointDataDerived > & | joint_data, |
const JointDataTpl< Scalar, Options, JointCollectionTpl > & | joint_data_generic | ||
) |
Definition at line 293 of file joint-generic.hpp.
bool pinocchio::operator!= | ( | const JointModelBase< JointModelDerived > & | joint_model, |
const JointModelTpl< Scalar, Options, JointCollectionTpl > & | joint_model_generic | ||
) |
Definition at line 307 of file joint-generic.hpp.
MotionRef<const Vector6Like> pinocchio::operator* | ( | const ConstraintIdentityTpl< Scalar, Options > & | , |
const Eigen::MatrixBase< Vector6Like > & | v | ||
) |
Definition at line 103 of file joint-free-flyer.hpp.
MultiplicationOp<InertiaTpl<Scalar,Options>,ConstraintDerived>::ReturnType pinocchio::operator* | ( | const InertiaTpl< Scalar, Options > & | Y, |
const ConstraintBase< ConstraintDerived > & | constraint | ||
) |
 .
Operation Y * S used in the CRBA algorithm for instance
Definition at line 112 of file constraint-base.hpp.
|
inline |
Definition at line 115 of file joint-free-flyer.hpp.
MultiplicationOp<Eigen::MatrixBase<MatrixDerived>,ConstraintDerived>::ReturnType pinocchio::operator* | ( | const Eigen::MatrixBase< MatrixDerived > & | Y, |
const ConstraintBase< ConstraintDerived > & | constraint | ||
) |
 .
Operation Y_matrix * S used in the ABA algorithm for instance
Definition at line 122 of file constraint-base.hpp.
internal::RHSScalarMultiplication<MotionDerived,typename MotionDerived::Scalar>::ReturnType pinocchio::operator* | ( | const typename MotionDerived::Scalar & | alpha, |
const MotionBase< MotionDerived > & | motion | ||
) |
Definition at line 122 of file motion-base.hpp.
Eigen::Matrix<S1,6,3,O1> pinocchio::operator* | ( | const InertiaTpl< S1, O1 > & | Y, |
const ConstraintSphericalZYXTpl< S2, O2 > & | S | ||
) |
Definition at line 183 of file joint-spherical-ZYX.hpp.
traits<F1>::ForcePlain pinocchio::operator* | ( | const typename traits< F1 >::Scalar | alpha, |
const ForceDense< F1 > & | f | ||
) |
Basic operations specialization.
Definition at line 193 of file force-dense.hpp.
const MatrixMatrixProduct< typename Eigen::internal::remove_const<typename SizeDepType<3>::ColsReturn<Matrix6Like>::ConstType>::type, typename ConstraintSphericalZYXTpl<S2,O2>::Matrix3 >::type pinocchio::operator* | ( | const Eigen::MatrixBase< Matrix6Like > & | Y, |
const ConstraintSphericalZYXTpl< S2, O2 > & | S | ||
) |
Definition at line 203 of file joint-spherical-ZYX.hpp.
traits<M1>::MotionPlain pinocchio::operator* | ( | const typename traits< M1 >::Scalar | alpha, |
const MotionDense< M1 > & | v | ||
) |
Definition at line 243 of file motion-dense.hpp.
|
inline |
Definition at line 302 of file joint-spherical.hpp.
|
inline |
Definition at line 317 of file joint-spherical.hpp.
|
inline |
Definition at line 347 of file joint-planar.hpp.
|
inline |
Definition at line 378 of file joint-planar.hpp.
|
inline |
Definition at line 380 of file joint-translation.hpp.
|
inline |
Definition at line 395 of file joint-translation.hpp.
|
inline |
Definition at line 113 of file motion-zero.hpp.
|
inline |
Definition at line 118 of file motion-zero.hpp.
MotionDerived::MotionPlain pinocchio::operator+ | ( | const MotionPrismaticTpl< Scalar, Options, axis > & | m1, |
const MotionDense< MotionDerived > & | m2 | ||
) |
Definition at line 162 of file joint-prismatic.hpp.
|
inline |
Definition at line 170 of file joint-prismatic-unaligned.hpp.
|
inline |
Definition at line 171 of file joint-translation.hpp.
|
inline |
Definition at line 178 of file joint-spherical.hpp.
|
inline |
Definition at line 179 of file joint-revolute-unaligned.hpp.
|
inline |
Definition at line 192 of file joint-planar.hpp.
MotionDerived::MotionPlain pinocchio::operator+ | ( | const MotionRevoluteTpl< S1, O1, axis > & | m1, |
const MotionDense< MotionDerived > & | m2 | ||
) |
Definition at line 316 of file joint-revolute.hpp.
std::ostream & pinocchio::operator<< | ( | std::ostream & | os, |
const LieGroupBase< Derived > & | lg | ||
) |
Definition at line 21 of file cartesian-product-liegroups.cpp.
std::ostream & pinocchio::operator<< | ( | std::ostream & | os, |
const LieGroupGenericTpl< LieGroupCollection > & | lg | ||
) |
Definition at line 26 of file cartesian-product-liegroups.cpp.
|
inline |
Definition at line 130 of file joint-composite.hpp.
|
inline |
Definition at line 151 of file src/multibody/frame.hpp.
|
inline |
Definition at line 493 of file joint-composite.hpp.
bool pinocchio::operator== | ( | const JointDataBase< JointDataDerived > & | joint_data, |
const JointDataTpl< Scalar, Options, JointCollectionTpl > & | joint_data_generic | ||
) |
Definition at line 285 of file joint-generic.hpp.
bool pinocchio::operator== | ( | const JointModelBase< JointModelDerived > & | joint_model, |
const JointModelTpl< Scalar, Options, JointCollectionTpl > & | joint_model_generic | ||
) |
Definition at line 300 of file joint-generic.hpp.
EIGEN_STRONG_INLINE MotionDerived::MotionPlain pinocchio::operator^ | ( | const MotionDense< MotionDerived > & | m1, |
const MotionPrismaticTpl< S2, O2, axis > & | m2 | ||
) |
Definition at line 173 of file joint-prismatic.hpp.
|
inline |
Definition at line 178 of file joint-prismatic-unaligned.hpp.
|
inline |
Definition at line 189 of file joint-revolute-unaligned.hpp.
traits<M1>::MotionPlain pinocchio::operator^ | ( | const MotionDense< M1 > & | v1, |
const MotionDense< M2 > & | v2 | ||
) |
Basic operations specialization.
Definition at line 233 of file motion-dense.hpp.
traits<F1>::ForcePlain pinocchio::operator^ | ( | const MotionDense< M1 > & | v, |
const ForceBase< F1 > & | f | ||
) |
Definition at line 238 of file motion-dense.hpp.
|
inline |
Definition at line 293 of file joint-spherical.hpp.
EIGEN_STRONG_INLINE MotionDerived::MotionPlain pinocchio::operator^ | ( | const MotionDense< MotionDerived > & | m1, |
const MotionRevoluteTpl< S2, O2, axis > & | m2 | ||
) |
Definition at line 327 of file joint-revolute.hpp.
|
inline |
Definition at line 339 of file joint-planar.hpp.
|
inline |
Definition at line 371 of file joint-translation.hpp.
const Scalar pinocchio::PI | ( | ) |
Returns the value of PI according to the template parameters Scalar.
Scalar | The scalar type of the return pi value |
Definition at line 26 of file src/math/fwd.hpp.
typedef pinocchio::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointData | ) |
typedef pinocchio::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointModel | ) |
pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER | ( | Parent | ) |
Simple model checker, that assert that model.parents is indeed a tree.
pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER | ( | CRBA | ) |
pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER | ( | ABA | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | equal_to_op | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | not_equal_to_op | , |
! | |||
) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | less_than_op | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | greater_than_op | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | less_than_or_equal_to_op | , |
<= | |||
) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | greater_than_or_equal_to_op | , |
>= | |||
) |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix3 | ) | const |
Orthogonal projection of a matrix on the SO(3) manifold.
[in] | mat | A 3x3 matrix to project on SO(3). |
Definition at line 79 of file rotation.hpp.
|
inline |
|
inline |
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
|
inline |
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
[in] | model | Model of the kinematic tree on which the integration operation is performed. |
[in] | q | Initial configuration (size model.nq) |
[in] | v | Joint velocity (size model.nv) |
|
inline |
Interpolate two configurations for a given model.
Squared distance between two configuration vectors.
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1.
[in] | model | Model of the kinematic tree on which the interpolation operation is performed. |
[in] | q0 | Initial configuration vector (size model.nq) |
[in] | q1 | Final configuration vector (size model.nq) |
[in] | u | u in [0;1] position along the interpolation. |
[in] | model | Model of the kinematic tree on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Final configuration (size model.nq) |
[in] | model | Model of the kinematic tree on which the squared distance operation is performed. |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
|
inline |
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1.
Squared distance between two configurations.
[in] | model | Model of the kinematic tree on which the difference operation is performed. |
[in] | q0 | Initial configuration (size model.nq) |
[in] | q1 | Finial configuration (size model.nq) |
[in] | model | Model of the kinematic tree on which the squared distance operation is performed. |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS | ( | (typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType) | ) | const |
Generate a configuration vector uniformly sampled among given limits.
[in] | model | Model of the kinematic tree on which the uniform sampling operation is performed. |
[in] | lowerLimits | Joints lower limits (size model.nq). |
[in] | upperLimits | Joints upper limits (size model.nq). |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS | ( | (typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType) | ) | const |
Generate a configuration vector uniformly sampled among provided limits.
[in] | model | Model of the kinematic tree on which the uniform sampling operation is performed. |
[in] | lowerLimits | Joints lower limits (size model.nq). |
[in] | upperLimits | Joints upper limits (size model.nq). |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS | ( | (typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType) | ) | const |
Generate a configuration vector uniformly sampled among the joint limits of the specified Model.
[in] | model | Model of the kinematic tree on which the uniform sampling operation is performed. |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS | ( | (typename ModelTpl< Scalar, Options, JointCollectionTpl >::ConfigVectorType) | ) | const |
Generate a configuration vector uniformly sampled among the joint limits of the specified Model.
[in] | model | Model of the kinematic tree on which the uniform sampling operation is performed. |
|
inline |
Definition at line 122 of file joint-free-flyer.hpp.
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelRevoluteUnboundedUnalignedTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelFreeFlyerTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelSphericalZYXTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelSphericalTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelPlanarTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelTranslationTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelPrismaticUnalignedTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelRevoluteUnalignedTpl | ) |
|
inline |
Computes the potential energy of the system, i.e. the potential energy linked to the gravity field. The result is accessible through data.potential_energy.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | update_kinematics | If true, first apply the forward kinematics on the kinematic tree. |
Definition at line 156 of file energy.hpp.
|
inline |
Returns the current version of Pinocchio as a string using the following standard: PINOCCHIO_MINOR_VERSION.PINOCCHIO_MINOR_VERSION.PINOCCHIO_PATCH_VERSION.
Definition at line 21 of file src/utils/version.hpp.
|
inline |
|
inline |
void pinocchio::randomConfiguration | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | lowerLimits, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | upperLimits, | ||
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Generate a configuration vector uniformly sampled among provided limits.
[in] | model | Model of the system on which the random configuration operation is performed. |
[in] | lowerLimits | Joints lower limits (size model.nq). |
[in] | upperLimits | Joints upper limits (size model.nq). |
[out] | qout | The resulting configuration vector (size model.nq). |
[in] | model | Model of the system on which the random configuration operation is performed. |
[in] | lowerLimits | Joints lower limits (size model.nq). |
[in] | upperLimits | Joints upper limits (size model.nq). |
[out] | qout | The resulting configuration vector (size model.nq). |
Definition at line 224 of file joint-configuration.hpp.
void pinocchio::randomConfiguration | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | lowerLimits, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | upperLimits, | ||
const Eigen::MatrixBase< ReturnType > & | qout | ||
) |
Generate a configuration vector uniformly sampled among provided limits.
[in] | model | Model of the system on which the random configuration operation is performed. |
[in] | lowerLimits | Joints lower limits (size model.nq). |
[in] | upperLimits | Joints upper limits (size model.nq). |
[out] | qout | The resulting configuration vector (size model.nq). |
Definition at line 224 of file joint-configuration.hpp.
|
inline |
Generate a random string composed of alphanumeric symbols of a given length.
len The length of the output string.
Definition at line 21 of file string-generator.hpp.
|
inline |
Retrieve the path of the file whose path is given in URL-format. Currently convert from the following patterns : package:// or file://.
[in] | string | The path given in the url-format |
[in] | package_dirs | A list of packages directories where to search for files if its pattern starts with package:// |
|
inline |
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system and the desired joint accelerations.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
void pinocchio::rnea | ( | const int | num_threads, |
ModelPoolTpl< Scalar, Options, JointCollectionTpl > & | pool, | ||
const Eigen::MatrixBase< ConfigVectorPool > & | q, | ||
const Eigen::MatrixBase< TangentVectorPool1 > & | v, | ||
const Eigen::MatrixBase< TangentVectorPool2 > & | a, | ||
const Eigen::MatrixBase< TangentVectorPool3 > & | tau | ||
) |
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system and the desired joint accelerations.
JointCollection | Collection of Joint types. |
ConfigVectorPool | Matrix type of the joint configuration vector. |
TangentVectorPool1 | Matrix type of the joint velocity vector. |
TangentVectorPool2 | Matrix type of the joint acceleration vector. |
TangentVectorPool3 | Matrix type of the joint torque vector. |
[in] | pool | Pool containing model and data for parallel computations. |
[in] | num_threads | Number of threads used for parallel computations. |
[in] | q | The joint configuration vector (dim model.nq x batch_size). |
[in] | v | The joint velocity vector (dim model.nv x batch_size). |
[in] | a | The joint acceleration vector (dim model.nv x batch_size). |
[out] | tau | The joint torque vector (dim model.nv x batch_size). |
Definition at line 32 of file parallel/rnea.hpp.
|
inline |
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques according to the current state of the system, the desired joint accelerations and the external forces.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
TangentVectorType2 | Type of the joint acceleration vector. |
ForceDerived | Type of the external forces. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | q | The joint configuration vector (dim model.nq). |
[in] | v | The joint velocity vector (dim model.nv). |
[in] | a | The joint acceleration vector (dim model.nv). |
[in] | fext | Vector of external forces expressed in the local frame of the joints (dim model.njoints) |
PINOCCHIO_DLLAPI std::vector< std::string > pinocchio::rosPaths | ( | ) |
Parse the environment variables ROS_PACKAGE_PATH / AMENT_PREFIX_PATH and extract paths.
Definition at line 55 of file file-explorer.cpp.
|
inline |
Set a mesh scaling vector to each GeometryObject contained in the the GeometryModel.
param[in] geom_model The geometry model containing the collision objects. param[in] meshScale The scale to be applied to each GeometryObject
Definition at line 63 of file src/algorithm/geometry.hpp.
|
inline |
Set an isotropic mesh scaling to each GeometryObject contained in the the GeometryModel.
param[in] geom_model The geometry model containing the collision objects. param[in] meshScale The scale, to be applied to each GeometryObject, equally in all directions
Definition at line 79 of file src/algorithm/geometry.hpp.
|
inline |
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic chain.
[in] | jmodel | The JointModelVariant |
[in] | id | The index of joint in the kinematic chain |
[in] | q | The index in the full model configuration space corresponding to the first degree of freedom |
[in] | v | The index in the full model tangent space corresponding to the first joint tangent space degree |
|
inline |
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model.
jmodel | The JointModelVariant we want the shortname of the type held in |
Scalar pinocchio::sign | ( | const Scalar & | t | ) |
void pinocchio::SINCOS | ( | const S1 & | a, |
S2 * | sa, | ||
S3 * | ca | ||
) |
Computes sin/cos values of a given input scalar.
Scalar | Type of the input/output variables |
[in] | a | The input scalar from which we evalute the sin and cos. |
[out] | sa | Variable containing the sin of a. |
[out] | ca | Variable containing the cos of a. |
Definition at line 26 of file sincos.hpp.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
void pinocchio::squaredDistance | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1, | ||
const Eigen::MatrixBase< ReturnType > & | out | ||
) |
Squared distance between two configuration vectors.
[in] | model | Model of the system on which the squared distance operation is performed. |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
[out] | out | The corresponding squared distances for each joint (size model.njoints-1 = number of joints). |
Definition at line 179 of file joint-configuration.hpp.
void pinocchio::squaredDistance | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1, | ||
const Eigen::MatrixBase< ReturnType > & | out | ||
) |
Squared distance between two configuration vectors.
[in] | model | Model of the system on which the squared distance operation is performed. |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
[out] | out | The corresponding squared distances for each joint (size model.njoints-1 = number of joints). |
Definition at line 179 of file joint-configuration.hpp.
|
inline |
Overall squared distance between two configuration vectors.
[in] | model | Model we want to compute the distance |
[in] | q0 | Configuration 0 (size model.nq) |
[in] | q1 | Configuration 1 (size model.nq) |
Overall squared distance between two configuration vectors.
[in] | model | Model of the kinematic tree |
[in] | q0 | Configuration from (size model.nq) |
[in] | q1 | Configuration to (size model.nq) |
Definition at line 545 of file joint-configuration.hpp.
|
inline |
Overall squared distance between two configuration vectors, namely .
Overall squared distance between two configuration vectors.
[in] | model | Model of the kinematic tree |
[in] | q0 | Configuration from (size model.nq) |
[in] | q1 | Configuration to (size model.nq) |
Definition at line 545 of file joint-configuration.hpp.
|
inline |
Definition at line 13 of file fcl-pinocchio-conversions.hpp.
|
inline |
Definition at line 18 of file fcl-pinocchio-conversions.hpp.
void pinocchio::toRotationMatrix | ( | const Eigen::MatrixBase< Vector3 > & | axis, |
const Scalar & | cos_value, | ||
const Scalar & | sin_value, | ||
const Eigen::MatrixBase< Matrix3 > & | res | ||
) |
Computes a rotation matrix from a vector and values of sin and cos orientations values.
Definition at line 24 of file rotation.hpp.
|
inline |
Visit a JointDataTpl through JointUInertiaVisitor to get the U matrix of the inertia matrix decomposition.
[in] | jdata | The joint data to visit. |
|
inline |
Visit a JointDataTpl through JointUDInvInertiaVisitor to get U*D^{-1} matrix of the inertia matrix decomposition.
[in] | jdata | The joint data to visit. |
|
inline |
Inverse of skew operator. From a given skew-symmetric matrix M of dimension 3x3, it extracts the supporting vector, i.e. the entries of M. Mathematically speacking, it computes such that .
[in] | M | a 3x3 skew symmetric matrix. |
[out] | v | the 3d vector representation of M. |
|
inline |
Inverse of skew operator. From a given skew-symmetric matrix M of dimension 3x3, it extracts the supporting vector, i.e. the entries of M. Mathematically speacking, it computes such that .
[in] | M | a 3x3 matrix. |
|
inline |
Updates the placement of the given frame.
[in] | model | The kinematic model. |
data | Data associated to model. | |
[in] | frame_id | Id of the operational Frame. |
|
inline |
Updates the position of each frame contained in the model.
JointCollection | Collection of Joint types. |
[in] | model | The kinematic model. |
data | Data associated to model. |
|
inline |
Apply a forward kinematics and update the placement of the geometry objects.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | geom_model | The geometry model containing the collision objects. |
[out] | geom_data | The geometry data containing the placements of the collision objects. See oMg field in GeometryData. |
[in] | q | The joint configuration vector (dim model.nq). |
|
inline |
Update the placement of the geometry objects according to the current joint placements contained in data.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | geom_model | The geometry model containing the collision objects. |
[out] | geom_data | The geometry data containing the placements of the collision objects. See oMg field in GeometryData. |
|
inline |
Update the global placement of the joints oMi according to the relative placements of the joints.
JointCollection | Collection of Joint types. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & pinocchio::lowerLimits |
Definition at line 902 of file joint-configuration.hpp.
JointCollectionTpl & pinocchio::model |
Definition at line 746 of file joint-configuration.hpp.
pinocchio::Options |
Definition at line 746 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & pinocchio::q |
Definition at line 746 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & pinocchio::q0 |
Definition at line 784 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & pinocchio::q1 |
Definition at line 784 of file joint-configuration.hpp.
pinocchio.submodules = inspect.getmembers(pinocchio_pywrap, inspect.ismodule) |
Definition at line 16 of file bindings/python/pinocchio/__init__.py.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > const Scalar & pinocchio::u |
Definition at line 784 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & pinocchio::upperLimits |
Definition at line 902 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & pinocchio::v |
Definition at line 746 of file joint-configuration.hpp.
bool pinocchio.WITH_HPP_FCL_BINDINGS = True |
Definition at line 24 of file bindings/python/pinocchio/__init__.py.