Main pinocchio namespace. More...
Namespaces | |
buildModels | |
Build simple models. | |
casadi | |
cholesky | |
Cholesky decompositions. | |
container | |
Specialized containers. | |
context | |
cppad | |
cppadcg | |
deprecated | |
deprecation | |
details | |
explog | |
fcl | |
fix | |
forceSet | |
Group force actions. | |
fusion | |
helper | |
impl | |
internal | |
lua | |
Lua parsing. | |
math | |
mjcf | |
motionSet | |
Group motion actions. | |
mpfr | |
python | |
quaternion | |
Quaternion operations. | |
robot_wrapper | |
romeo_wrapper | |
rpy | |
Roll-pitch-yaw operations. | |
sdf | |
serialization | |
shortcuts | |
srdf | |
SRDF parsing. | |
urdf | |
URDF parsing. | |
utils | |
visualize | |
windows_dll_manager | |
Enumerations | |
enum | { SELF = 0 } |
enum | { MAX_JOINT_NV = 6 } |
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 | ContactType { CONTACT_3D = 0, CONTACT_6D, CONTACT_UNDEFINED } |
More... | |
enum | Convention { Convention::WORLD = 0, Convention::LOCAL = 1 } |
List of convention to call algorithms. More... | |
enum | FrameType { OP_FRAME = 0x1 << 0, JOINT = 0x1 << 1, FIXED_JOINT = 0x1 << 2, BODY, 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 } |
Various conventions to express the velocity of a moving frame. More... | |
Functions | |
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, const Convention rf=Convention::LOCAL) |
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model and the external forces. 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, const Convention convention=Convention::LOCAL) |
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 ConfigVectorPool , typename TangentVectorPool1 , typename TangentVectorPool2 , typename TangentVectorPool3 > | |
void | abaInParallel (const size_t 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 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 > | |
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... | |
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... | |
void | appendGeometryModel (GeometryModel &geom_model1, const GeometryModel &geom_model2) |
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 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> | |
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... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Model | appendModel< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Model &, const FrameIndex, const SE3Tpl< context::Scalar, context::Options > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | appendModel< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Model &, const FrameIndex, const SE3Tpl< context::Scalar, context::Options > &, context::Model &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | appendModel< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Model &, const GeometryModel &, const GeometryModel &, const FrameIndex, const SE3Tpl< context::Scalar, context::Options > &, context::Model &, GeometryModel &) |
PINOCCHIO_PARSERS_DLLAPI 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 > | |
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... | |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType | bodyRegressor< context::Motion, context::Motion > (const MotionDense< context::Motion > &, const MotionDense< context::Motion > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | bodyRegressor< context::Motion, context::Motion, context::BodyRegressorType > (const MotionDense< context::Motion > &, const MotionDense< context::Motion > &, const Eigen::MatrixBase< context::BodyRegressorType > &) |
void | buildAllJointsModel (Model &model) |
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, 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, 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | buildReducedModel< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const GeometryModel &, const std::vector< JointIndex > &, const Eigen::MatrixBase< context::VectorXs > &, context::Model &, GeometryModel &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Model | buildReducedModel< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const std::vector< JointIndex > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | buildReducedModel< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const std::vector< JointIndex >, const Eigen::MatrixBase< context::VectorXs > &, context::Model &) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, template< typename S, int O > class ConstraintCollectionTpl> | |
void | calc (const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel, ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata, const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename VectorLike , typename Matrix6Type > | |
void | calc_aba (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< VectorLike > &armature, 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 TangentVectorType > | |
void | calc_first_order (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Blank blank, 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 , 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> | |
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, 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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Vector3 & | centerOfMass< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, const bool computeSubtreeComs) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Vector3 & | centerOfMass< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, KinematicLevel, const bool computeSubtreeComs) |
template<typename Scalar , int Options, typename ForceIn > | |
ForceIn::ForcePlain | changeReferenceFrame (const SE3Tpl< Scalar, Options > &placement, const ForceDense< ForceIn > &f_in, const ReferenceFrame rf_in, const ReferenceFrame rf_out) |
template<typename Scalar , int Options, typename ForceIn , typename ForceOut > | |
void | changeReferenceFrame (const SE3Tpl< Scalar, Options > &placement, const ForceDense< ForceIn > &f_in, const ReferenceFrame rf_in, const ReferenceFrame rf_out, ForceDense< ForceOut > &f_out) |
template<typename Scalar , int Options, typename MotionIn > | |
MotionIn::MotionPlain | changeReferenceFrame (const SE3Tpl< Scalar, Options > &placement, const MotionDense< MotionIn > &m_in, const ReferenceFrame rf_in, const ReferenceFrame rf_out) |
template<typename Scalar , int Options, typename MotionIn , typename MotionOut > | |
void | changeReferenceFrame (const SE3Tpl< Scalar, Options > &placement, const MotionDense< MotionIn > &m_in, const ReferenceFrame rf_in, const ReferenceFrame rf_out, MotionDense< MotionOut > &m_out) |
template<typename Scalar , typename Any > | |
bool | check_expression_if_real (const Any &expression) |
template<typename Scalar , bool default_value, typename Any > | |
bool | check_expression_if_real (const Any &expression) |
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 Motion1 , typename Motion2 , typename Vector3Like > | |
void | classicAcceleration (const MotionDense< Motion1 > &spatial_velocity, const MotionDense< Motion2 > &spatial_acceleration, const Eigen::MatrixBase< Vector3Like > &res) |
Computes the classic acceleration from a given spatial velocity and spatial acceleration. More... | |
template<typename Motion1 , typename Motion2 , typename SE3Scalar , int SE3Options, typename Vector3Like > | |
void | classicAcceleration (const MotionDense< Motion1 > &spatial_velocity, const MotionDense< Motion2 > &spatial_acceleration, const SE3Tpl< SE3Scalar, SE3Options > &placement, const Eigen::MatrixBase< Vector3Like > &res) |
Computes the classic acceleration of a given frame B knowing the spatial velocity and spatial acceleration of a frame A and the relative placement between these two frames. More... | |
classicAcceleration (spatial_velocity, spatial_acceleration, placement, res) | |
classicAcceleration (spatial_velocity, spatial_acceleration, res) | |
template<typename T > | |
bool | compare_shared_ptr (const std::shared_ptr< T > &ptr1, const std::shared_ptr< T > &ptr2) |
Compares two std::shared_ptr. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
The derivatives of the Articulated-Body algorithm. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const container::aligned_vector< ForceTpl< Scalar, Options >> &fext) |
The derivatives of the Articulated-Body algorithm with external forces. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename MatrixType1 , typename MatrixType2 , typename MatrixType3 > | |
void | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, 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. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > | |
std::enable_if< ConfigVectorType::IsVectorAtCompileTime||TangentVectorType1::IsVectorAtCompileTime||TangentVectorType2::IsVectorAtCompileTime, void >::type | 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 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 , 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 MatrixType1 , typename MatrixType2 , typename MatrixType3 > | |
std::enable_if< !(MatrixType1::IsVectorAtCompileTime||MatrixType2::IsVectorAtCompileTime||MatrixType3::IsVectorAtCompileTime), void >::type | computeABADerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, 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. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeABADerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeABADerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, const container::aligned_vector< ForceTpl< context::Scalar, context::Options >> &) |
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> | |
void | computeBodyRadius (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const GeometryModel &geom_model, GeometryData &geom_data) |
template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeBodyRadius< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const GeometryModel &, GeometryData &) |
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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI ForceTpl< context::Scalar, context::Options > & | computeCentroidalMomentum< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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... | |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI ForceTpl< context::Scalar, context::Options > & | computeCentroidalMomentumTimeVariation< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
bool | computeCollision (const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id) |
Compute the collision status between a SINGLE collision pair. The result is store in the collisionResults vector. More... | |
bool | computeCollision (const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id, fcl::CollisionRequest &collision_request) |
Compute the collision status between a SINGLE collision pair. The result is store in the collisionResults vector. More... | |
template<typename BroadPhaseManagerDerived > | |
bool | computeCollisions (BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback) |
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeometryPlacements and broadphase_manager.update() have been called first. More... | |
template<typename BroadPhaseManagerDerived > | |
bool | computeCollisions (BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, const bool stopAtFirstCollision=false) |
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeometryPlacements and broadphase_manager.update() have been called first. More... | |
bool | computeCollisions (const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false) |
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeometryPlacements has been called first. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename BroadPhaseManagerDerived , typename ConfigVectorType > | |
bool | computeCollisions (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback, const Eigen::MatrixBase< ConfigVectorType > &q) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename BroadPhaseManagerDerived , typename ConfigVectorType > | |
bool | computeCollisions (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, const Eigen::MatrixBase< ConfigVectorType > &q, const bool stopAtFirstCollision=false) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
bool | computeCollisions (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 PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool | computeCollisions< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const GeometryModel &, GeometryData &, const Eigen::MatrixBase< context::VectorXs > &, const bool stopAtFirstCollision) |
template<typename BroadPhaseManagerDerived , typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorPool , typename CollisionVectorResult > | |
void | computeCollisionsInParallel (const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< CollisionVectorResult > &res, const bool stopAtFirstCollisionInConfiguration=false, const bool stopAtFirstCollisionInBatch=false) |
template<typename BroadPhaseManagerDerived , typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
void | computeCollisionsInParallel (const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > &pool, const std::vector< Eigen::MatrixXd > &trajectories, std::vector< VectorXb > &res, const bool stopAtFirstCollisionInTrajectory=false) |
Evaluate the collision over a set of trajectories and return whether a trajectory contains a collision. More... | |
bool | computeCollisionsInParallel (const size_t 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 | computeCollisionsInParallel (const size_t 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 | computeCollisionsInParallel (const size_t num_threads, GeometryPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< CollisionVectorResult > &res, const bool stopAtFirstCollisionInConfiguration=false, const bool stopAtFirstCollisionInBatch=false) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class ConstraintModelAllocator , class ConstraintDataAllocator > | |
void | computeConstraintDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class ConstraintModelAllocator , class ConstraintDataAllocator , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 , typename MatrixType4 , typename MatrixType5 , typename MatrixType6 > | |
void | computeConstraintDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const Eigen::MatrixBase< MatrixType1 > &ddq_partial_dq, const Eigen::MatrixBase< MatrixType2 > &ddq_partial_dv, const Eigen::MatrixBase< MatrixType3 > &ddq_partial_dtau, const Eigen::MatrixBase< MatrixType4 > &lambda_partial_dq, const Eigen::MatrixBase< MatrixType5 > &lambda_partial_dv, const Eigen::MatrixBase< MatrixType6 > &lambda_partial_dtau) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class ConstraintModelAllocator , class ConstraintDataAllocator > | |
void | computeConstraintDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const ProximalSettingsTpl< Scalar > &settings) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class ConstraintModelAllocator , class ConstraintDataAllocator , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 , typename MatrixType4 , typename MatrixType5 , typename MatrixType6 > | |
void | computeConstraintDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const ProximalSettingsTpl< Scalar > &settings, const Eigen::MatrixBase< MatrixType1 > &ddq_partial_dq, const Eigen::MatrixBase< MatrixType2 > &ddq_partial_dv, const Eigen::MatrixBase< MatrixType3 > &ddq_partial_dtau, const Eigen::MatrixBase< MatrixType4 > &lambda_partial_dq, const Eigen::MatrixBase< MatrixType5 > &lambda_partial_dv, const Eigen::MatrixBase< MatrixType6 > &lambda_partial_dtau) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, context::Data &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, context::Data &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &, const ProximalSettingsTpl< context::Scalar > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs > (const context::Model &, context::Data &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs > (const context::Model &, context::Data &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &, const ProximalSettingsTpl< context::Scalar > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename VectorLikeC , class ConstraintModelAllocator , class ConstraintDataAllocator , class CoulombFrictionConelAllocator , typename VectorLikeR , typename VectorLikeGamma , typename VectorLikeImp > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | computeContactImpulses (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< VectorLikeC > &c_ref, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeImp > &impulse_guess=boost::none) |
Compute the contact impulses given a target velocity of contact points. More... | |
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: More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , class ModelAllocator , class DataAllocator , typename MatrixType > | |
void | computeDampedDelassusMatrixInverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > &contact_data, const Eigen::MatrixBase< MatrixType > &damped_delassus_inverse, const Scalar mu, const bool scaled=false, const bool Pv=true) |
Computes the inverse of the Delassus matrix associated to a set of given constraints. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , class ModelAllocator , class DataAllocator , typename MatrixType > | |
void | computeDelassusMatrix (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > &contact_data, const Eigen::MatrixBase< MatrixType > &delassus, const Scalar mu=0) |
Computes the Delassus matrix associated to a set of given constraints. More... | |
fcl::DistanceResult & | computeDistance (const GeometryModel &geom_model, GeometryData &geom_data, const PairIndex pair_id) |
Compute the minimal distance between collision objects of a SINGLE collison pair. More... | |
std::size_t | computeDistances (const GeometryModel &geom_model, GeometryData &geom_data) |
Compute the minimal distance between collision objects of a ALL collison pair. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
std::size_t | computeDistances (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
std::size_t | computeDistances (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q) |
template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI std::size_t | computeDistances< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const GeometryModel &, GeometryData &, const Eigen::MatrixBase< context::VectorXs > &) |
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 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 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::Matrix6xs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const FrameIndex, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::Matrix6xs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &) |
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 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) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs | computeFrameKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeFrameKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &) |
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: More... | |
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, class ConstraintModelAllocator , class ConstraintDataAllocator > | |
void | computeImpulseDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const Scalar r_coeff, const ProximalSettingsTpl< Scalar > &settings) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class ConstraintModelAllocator , class ConstraintDataAllocator , typename MatrixType1 , typename MatrixType2 , typename MatrixType3 , typename MatrixType4 > | |
void | computeImpulseDynamicsDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const Scalar r_coeff, const ProximalSettingsTpl< Scalar > &settings, const Eigen::MatrixBase< MatrixType1 > &dvimpulse_partial_dq, const Eigen::MatrixBase< MatrixType2 > &dvimpulse_partial_dv, const Eigen::MatrixBase< MatrixType3 > &impulse_partial_dq, const Eigen::MatrixBase< MatrixType4 > &impulse_partial_dv) |
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 joint_id, const Eigen::MatrixBase< Matrix6Like > &J) |
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store the result in the input argument J. 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 > | |
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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs & | computeJointJacobians< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeJointKinematicHessians< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeJointKinematicHessians< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &) |
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 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) |
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 SE3Tpl< Scalar, Options > &placement, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs | computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs | computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame, const SE3Tpl< context::Scalar, context::Options > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame, const SE3Tpl< context::Scalar, context::Options > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs & | computeJointTorqueRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | computeKineticEnergy< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Data::RowVectorXs & | computeKineticEnergyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
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: More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeKKTContactDynamicMatrixInverse< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::MatrixXs, context::MatrixXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const context::Scalar &) |
template<typename MatrixLike , typename VectorLike > | |
void | computeLargestEigenvector (const MatrixLike &mat, const Eigen::PlainObjectBase< VectorLike > &_eigenvector_est, const int max_it=10, const typename MatrixLike::Scalar rel_tol=1e-8) |
Compute the lagest eigenvector of a given matrix according to a given eigenvector estimate. More... | |
template<typename MatrixLike > | |
Eigen::Matrix< typename MatrixLike::Scalar, MatrixLike::RowsAtCompileTime, 1 > | computeLargestEigenvector (const MatrixLike &mat, const int max_it=10, const typename MatrixLike::Scalar rel_tol=1e-8) |
Compute the lagest eigenvector of a given matrix. More... | |
template<typename MatrixLike > | |
Eigen::Matrix< typename MatrixLike::Scalar, MatrixLike::RowsAtCompileTime, 1 > | computeLowestEigenvector (const MatrixLike &mat, const bool compute_largest=true, const int max_it=10, const typename MatrixLike::Scalar rel_tol=1e-8) |
Compute the lagest eigenvector of a given matrix. More... | |
template<typename MatrixLike , typename VectorLike1 , typename VectorLike2 > | |
void | computeLowestEigenvector (const MatrixLike &mat, const Eigen::PlainObjectBase< VectorLike1 > &largest_eigenvector_est, const Eigen::PlainObjectBase< VectorLike2 > &lowest_eigenvector_est, const bool compute_largest=true, const int max_it=10, const typename MatrixLike::Scalar rel_tol=1e-8) |
Compute the lagest eigenvector of a given matrix according to a given eigenvector estimate. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Scalar | computeMechanicalEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes the mechanical energy of the system stored in data.mechanical_energy. The result is accessible through data.kinetic_energy. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | |
Scalar | computeMechanicalEnergy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) |
Computes the mechanical energy of the system stored in data.mechanical_energy. The result is accessible through data.kinetic_energy. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | computeMechanicalEnergy< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & | computeMinverse (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) |
Computes the inverse of the joint space inertia matrix using Articulated Body formulation. Compared to the complete signature computeMinverse<Scalar,Options,ConfigVectorType>, this version assumes that ABA has been called first. More... | |
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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::RowMatrixXs & | computeMinverse< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | computePotentialEnergy< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::RowVectorXs & | computePotentialEnergyRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Data::RowVectorXs & | computePotentialEnergyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &) |
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 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 , 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 > | |
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 , 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 > | |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix3x & | computeStaticRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &) |
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: More... | |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | computeSubtreeMasses< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | computeTotalMass< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | computeTotalMass< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ContactModelAllocator , class ContactDataAllocator > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | constrainedABA (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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ContactModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ContactDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings) |
The constrained Articulated Body Algorithm (constrainedABA). It computes constrained forward dynamics, aka the joint accelerations and constraint forces given the current state, actuation and the constraints on the system. All the quantities are expressed in the LOCAL coordinate systems of the joint frames. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ConstraintModelAllocator , class ConstraintDataAllocator > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | constraintDynamics (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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas) |
Computes the forward dynamics with contact constraints according to a given list of Contact information. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ConstraintModelAllocator , class ConstraintDataAllocator > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | constraintDynamics (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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings) |
Computes the forward dynamics with contact constraints according to a given list of contact information. More... | |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs & | constraintDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs & | constraintDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &, ProximalSettingsTpl< context::Scalar > &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ModelAllocator , class DataAllocator > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | contactABA (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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > &contact_data) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs & | contactABA< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ConstraintModelAllocator , class ConstraintDataAllocator , class CoulombFrictionConelAllocator , typename VectorLikeR , typename VectorLikeGamma , typename VectorLikeLam > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | contactInverseDynamics (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, Scalar dt, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeLam > &lambda_guess=boost::none) |
The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the presence of contacts, 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> | |
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, 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, const Convention convention=Convention::LOCAL) |
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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs & | crba< context::Scalar, context::Options, JointCollectionDefaultTpl, Eigen::Ref< const context::VectorXs > > (const context::Model &, context::Data &, const Eigen::MatrixBase< Eigen::Ref< const context::VectorXs >> &, const Convention convention) |
template<typename Scalar , int Options, template< typename S, int O > class ConstraintCollectionTpl> | |
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > | createData (const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel) |
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 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, const ArgumentPosition arg) |
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<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, const ArgumentPosition arg) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dDifference< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dDifference< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | difference< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | difference< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | difference< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | difference< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
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 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, int self, const Eigen::MatrixBase< JacobianIn_t > &J_in, const Eigen::MatrixBase< JacobianOut_t > &J_out, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dIntegrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dIntegrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition, const AssignmentOperatorType) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dIntegrate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition, const AssignmentOperatorType) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dIntegrateTransport< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dIntegrateTransport< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | dIntegrateTransport< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const Eigen::MatrixBase< context::MatrixXs > &, const ArgumentPosition) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | distance< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | distance< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
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 Vector6Like > | |
SE3Tpl< typename Vector6Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options > | exp6 (const Eigen::MatrixBase< Vector6Like > &v) |
Exp: se3 -> SE3. 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... | |
PINOCCHIO_PARSERS_DLLAPI 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... | |
PINOCCHIO_PARSERS_DLLAPI 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... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
JointIndex | findCommonAncestor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, JointIndex joint1_id, JointIndex joint2_id, size_t &index_ancestor_in_support1, size_t &index_ancestor_in_support2) |
Computes the common ancestor between two joints belonging to the same kinematic tree. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex | findCommonAncestor< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, JointIndex, JointIndex, size_t &, size_t &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , typename ConstraintMatrixType , typename DriftVectorType > | |
const PINOCCHIO_DEPRECATED 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 PINOCCHIO_DEPRECATED 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 > | |
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 frame_id) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType & | frameBodyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, FrameIndex) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | framesForwardKinematics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getCenterOfMassVelocityDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix3x > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::Matrix3x > &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getClassicalAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame) |
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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Vector3 & | getComFromCrba< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6Like > | |
void | getConstraintJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const RigidConstraintModelTpl< Scalar, Options > &constraint_model, RigidConstraintDataTpl< Scalar, Options > &constraint_data, const Eigen::MatrixBase< Matrix6Like > &J) |
Computes the kinematic Jacobian associatied to a given constraint model. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getConstraintJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::MatrixXs > (const context::Model &, const context::Data &, const context::RigidConstraintModel &, context::RigidConstraintData &, const Eigen::MatrixBase< context::MatrixXs > &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename DynamicMatrixLike , class ConstraintModelAllocator , class ConstraintDataAllocator > | |
void | getConstraintsJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintDataAllocator > &constraint_model, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &constraint_data, const Eigen::MatrixBase< DynamicMatrixLike > &J) |
Computes the kinematic Jacobian associatied to a given set of constraint models. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getConstraintsJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::MatrixXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, const context::Data &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &, const Eigen::MatrixBase< context::MatrixXs > &) |
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: More... | |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs & | getCoriolisMatrix< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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 the data structure. More... | |
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 JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getFrameAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const FrameIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getFrameAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame) |
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, typename Matrix6xOut1 , typename Matrix6xOut2 , typename Matrix6xOut3 , typename Matrix6xOut4 > | |
void | getFrameAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, 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 spatial acceleration of a frame given by its relative placement, 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 JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > (const context::Model &, context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > (const context::Model &, context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
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> | |
MotionTpl< Scalar, Options > | getFrameClassicalAcceleration (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getFrameClassicalAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const FrameIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getFrameClassicalAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | getFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame reference_frame) |
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system, in the local world aligned frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians. 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 reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J) |
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system, in the local world aligned frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | getFrameJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame reference_frame) |
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame, and whose columns are either expressed in the LOCAL frame coordinate system, in the local world aligned frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians. 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 JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6xLike > &J) |
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame, and whose columns are either expressed in the LOCAL frame coordinate system, in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs | getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs | getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > (const context::Model &, context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &) |
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 WORLD frame (rf = WORLD), in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame or in the LOCAL frame (rf = LOCAL). More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameJacobianTimeVariation< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &) |
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> | |
MotionTpl< Scalar, Options > | getFrameVelocity (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getFrameVelocity< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const FrameIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getFrameVelocity< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xOut1 , typename Matrix6xOut2 > | |
void | getFrameVelocityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv) |
Computes the partial derivatives of the spatial velocity of a frame given by its relative placement, 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, 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 spatial velocity with respect to q and v. You must first call pinocchio::computeForwardKinematicsDerivatives to compute all the required quantities. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameVelocityDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs > (const context::Model &, const context::Data &, const JointIndex, const SE3Tpl< context::Scalar, context::Options > &, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getFrameVelocityDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs > (const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame, const Eigen::MatrixBase< context::Matrix6xs > &, const Eigen::MatrixBase< context::Matrix6xs > &) |
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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix3x & | getJacobianComFromCrba< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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> | |
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | getJointJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame) |
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame, in the local world aligned (rf = LOCAL_WORLD_ALIGNED) 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 | getJointJacobian (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &J) |
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame options. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs | getJointJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame) |
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 joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &dJ) |
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (rf = WORLD), in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame or in the local frame (rf = LOCAL) of the joint. 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> | |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI Tensor< context::Scalar, 3, context::Options > | getJointKinematicHessian< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | getJointKinematicHessian< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame, Tensor< context::Scalar, 3, context::Options > &) |
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 > | |
PINOCCHIO_DEPRECATED 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. More... | |
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, typename Matrix3xOut1 , typename Matrix3xOut2 , typename Matrix3xOut3 , typename Matrix3xOut4 > | |
void | getPointClassicAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &a_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut3 > &a_point_partial_dv, const Eigen::MatrixBase< Matrix3xOut4 > &a_point_partial_da) |
Computes the partial derivatives of the classic acceleration of a point given by its placement information w.r.t. the joint frame. 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_point_partial_dq. v_point_partial_dv is not computed it is equal to a_point_partial_da. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xOut1 , typename Matrix3xOut2 , typename Matrix3xOut3 , typename Matrix3xOut4 , typename Matrix3xOut5 > | |
void | getPointClassicAccelerationDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &v_point_partial_dv, const Eigen::MatrixBase< Matrix3xOut3 > &a_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut4 > &a_point_partial_dv, const Eigen::MatrixBase< Matrix3xOut5 > &a_point_partial_da) |
Computes the partial derivaties of the classic acceleration of a point given by its placement information w.r.t. to the joint frame. 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_point_partial_dq and v_point_partial_dv.. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix3xOut1 , typename Matrix3xOut2 > | |
void | getPointVelocityDerivatives (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const SE3Tpl< Scalar, Options > &placement, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix3xOut1 > &v_point_partial_dq, const Eigen::MatrixBase< Matrix3xOut2 > &v_point_partial_dv) |
Computes the partial derivatives of the velocity of a point given by its placement information w.r.t. the joint frame. You must first call computForwardKinematicsDerivatives before calling this function. More... | |
template<typename Scalar , int Options, class Allocator > | |
struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") RigidConstraintModelTpl size_t | getTotalConstraintSize (const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models) |
Contact model structure containg all the info describing the rigid contact model. 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl< context::Scalar, context::Options > | getVelocity< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame) |
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 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 , 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 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 PINOCCHIO_DEPRECATED 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 TangentVectorType1 , class ConstraintModelAllocator , class ConstraintDataAllocator > | |
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< TangentVectorType1 > &v_before, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const Scalar r_coeff, const ProximalSettingsTpl< Scalar > &settings) |
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 PINOCCHIO_DEPRECATED 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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs & | impulseDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > (const context::Model &, context::Data &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::RigidConstraintModelVector &, context::RigidConstraintDataVector &, const context::Scalar, const ProximalSettingsTpl< context::Scalar > &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class Allocator > | |
void | initConstraintDynamics (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models) |
Init the forward dynamics data according to the contact information contained in contact_models. More... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | initConstraintDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type > (const context::Model &, context::Data &, const context::RigidConstraintModelVector &) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class Allocator > | |
void | initPvDelassus (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, class Allocator > | |
void | initPvSolver (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models) |
Init the data according to the contact information contained in contact_models. 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | integrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | integrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | integrate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | integrate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | integrateCoeffWiseJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | integrateCoeffWiseJacobian< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::MatrixXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::MatrixXs > &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | interpolate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | interpolate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | interpolate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | interpolate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &, const Eigen::MatrixBase< context::VectorXs > &) |
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 ConstraintCollectionTpl, typename ConstraintDataDerived > | |
bool | isEqual (const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata_generic, const ConstraintDataBase< ConstraintDataDerived > &cdata) |
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 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 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 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool | isNormalized< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool | isNormalized< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool | isSameConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool | isSameConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const context::Scalar &) |
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 S, int O > class JointCollectionTpl, template< typename S, int O > class ConstraintCollectionTpl, typename JacobianMatrix > | |
void | jacobian (const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel, ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata, const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< JacobianMatrix > &jacobian_matrix) |
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 > | |
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, 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<typename MotionDerived > | |
Eigen::Matrix< typename MotionDerived::Scalar, 6, 6, MotionDerived::Options > | Jexp6 (const MotionDense< MotionDerived > &nu) |
Derivative of exp6 Computed as the inverse of Jlog6. 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 Matrix3Like1 , typename Matrix3Like2 > | |
void | Jlog3 (const Eigen::MatrixBase< Matrix3Like1 > &R, const Eigen::MatrixBase< Matrix3Like2 > &Jlog) |
Derivative of log3. 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 Scalar , int Options> | |
Eigen::Matrix< Scalar, 6, 6, Options > | Jlog6 (const SE3Tpl< Scalar, Options > &M) |
Derivative of log6. 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> | |
JointMotionSubspaceTpl< Eigen::Dynamic, Scalar, Options > | joint_motin_subspace_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 S, int O > class JointCollectionTpl> | |
JointDataTpl< Scalar, Options, JointCollectionTpl >::ConfigVector_t | joint_q (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector. 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 S, int O > class JointCollectionTpl> | |
JointDataTpl< Scalar, Options, JointCollectionTpl >::TangentVector_t | joint_v (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector. 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 joint_id) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType & | jointBodyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, JointIndex) |
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 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 Matrix4Like > | |
MotionTpl< typename Matrix4Like::Scalar, Eigen::internal::traits< Matrix4Like >::Options > | log6 (const Eigen::MatrixBase< Matrix4Like > &M) |
Log: SE3 -> se3. More... | |
template<typename Vector3Like , typename QuaternionLike > | |
MotionTpl< typename Vector3Like::Scalar, Vector3Like::Options > | log6 (const Eigen::QuaternionBase< QuaternionLike > &quat, const Eigen::MatrixBase< Vector3Like > &vec) |
Log: SE3 -> se3. More... | |
template<typename Scalar , int Options> | |
MotionTpl< Scalar, Options > | log6 (const SE3Tpl< Scalar, Options > &M) |
Log: SE3 -> se3. More... | |
template<typename M > | |
auto | make_const_ref (Eigen::MatrixBase< M > const &m) -> Eigen::Ref< typename M::PlainObject const > |
template<typename Derived > | |
Eigen::Ref< typename Derived::PlainObject > | make_ref (const Eigen::MatrixBase< Derived > &x) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | neutral< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | neutral< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | neutral< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | neutral< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &) |
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: More... | |
template<typename VectorLike > | |
void | normalize (const Eigen::MatrixBase< VectorLike > &vec) |
Normalize the input vector. More... | |
template<typename LieGroupCollection , class Config_t > | |
void | normalize (const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< Config_t > &qout) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | normalize< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | normalize< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &) |
template<typename Matrix3 > | |
void | normalizeRotation (const Eigen::MatrixBase< Matrix3 > &rot) |
Orthogonormalization procedure for a rotation matrix (closed enough to SO(3)). 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 | 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 | nv (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent 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, 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 LhsMatrixType , typename S , int O> | |
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > | operator* (const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs) |
template<typename M6Like , typename S2 , int O2> | |
Eigen::Matrix< S2, 6, 3, O2 > | operator* (const Eigen::MatrixBase< M6Like > &Y, const JointMotionSubspacePlanarTpl< S2, O2 > &) |
template<typename M6Like , typename S2 , int O2> | |
SizeDepType< 3 >::ColsReturn< M6Like >::ConstType | operator* (const Eigen::MatrixBase< M6Like > &Y, const JointMotionSubspaceSphericalTpl< S2, O2 > &) |
template<typename M6Like , typename S2 , int O2> | |
const SizeDepType< 3 >::ColsReturn< M6Like >::ConstType | operator* (const Eigen::MatrixBase< M6Like > &Y, const JointMotionSubspaceTranslationTpl< S2, O2 > &) |
template<typename Matrix6Like , typename S2 , int O2> | |
const MatrixMatrixProduct< typename Eigen::internal::remove_const< typename SizeDepType< 3 >::ColsReturn< Matrix6Like >::ConstType >::type, typename JointMotionSubspaceSphericalZYXTpl< S2, O2 >::Matrix3 >::type | operator* (const Eigen::MatrixBase< Matrix6Like > &Y, const JointMotionSubspaceSphericalZYXTpl< S2, O2 > &S) |
template<typename MatrixDerived , typename ConstraintDerived > | |
MultiplicationOp< Eigen::MatrixBase< MatrixDerived >, ConstraintDerived >::ReturnType | operator* (const Eigen::MatrixBase< MatrixDerived > &Y, const JointMotionSubspaceBase< ConstraintDerived > &constraint) |
More... | |
template<typename S1 , int O1, typename S2 , int O2> | |
InertiaTpl< S1, O1 >::Matrix6 | operator* (const InertiaTpl< S1, O1 > &Y, const JointMotionSubspaceIdentityTpl< S2, O2 > &) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S1, 6, 3, O1 > | operator* (const InertiaTpl< S1, O1 > &Y, const JointMotionSubspacePlanarTpl< S2, O2 > &) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S2, 6, 3, O2 > | operator* (const InertiaTpl< S1, O1 > &Y, const JointMotionSubspaceSphericalTpl< S2, O2 > &) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S1, 6, 3, O1 > | operator* (const InertiaTpl< S1, O1 > &Y, const JointMotionSubspaceSphericalZYXTpl< S2, O2 > &S) |
template<typename S1 , int O1, typename S2 , int O2> | |
Eigen::Matrix< S2, 6, 3, O2 > | operator* (const InertiaTpl< S1, O1 > &Y, const JointMotionSubspaceTranslationTpl< S2, O2 > &) |
template<typename Scalar , int Options, typename ConstraintDerived > | |
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType | operator* (const InertiaTpl< Scalar, Options > &Y, const JointMotionSubspaceBase< ConstraintDerived > &constraint) |
More... | |
template<typename Scalar , int Options, typename Vector6Like > | |
MotionRef< const Vector6Like > | operator* (const JointMotionSubspaceIdentityTpl< Scalar, Options > &, const Eigen::MatrixBase< Vector6Like > &v) |
template<class ConstraintDerived > | |
JointMotionSubspaceTransposeBase< ConstraintDerived >::StDiagonalMatrixSOperationReturnType | operator* (const JointMotionSubspaceTransposeBase< ConstraintDerived > &, const JointMotionSubspaceBase< ConstraintDerived > &S) |
template<typename _Scalar , int _Options, int _axis> | |
Eigen::Matrix< _Scalar, 1, 1, _Options > | operator* (const typename JointMotionSubspaceHelicalTpl< _Scalar, _Options, _axis >::TransposeConst &S_transpose, const JointMotionSubspaceHelicalTpl< _Scalar, _Options, _axis > &S) |
template<typename _Scalar , int _Options> | |
Eigen::Matrix< _Scalar, 1, 1, _Options > | operator* (const typename JointMotionSubspaceHelicalUnalignedTpl< _Scalar, _Options >::TransposeConst &S_transpose, const JointMotionSubspaceHelicalUnalignedTpl< _Scalar, _Options > &S) |
template<typename MotionDerived > | |
internal::RHSScalarMultiplication< MotionDerived, typename MotionDerived::Scalar >::ReturnType | operator* (const typename MotionDerived::Scalar &alpha, const MotionBase< MotionDerived > &motion) |
template<typename F1 > | |
traits< F1 >::ForcePlain | operator* (const typename traits< F1 >::Scalar alpha, const ForceDense< F1 > &f) |
Basic operations specialization. More... | |
template<typename M1 > | |
traits< M1 >::MotionPlain | operator* (const typename traits< M1 >::Scalar alpha, const MotionDense< M1 > &v) |
template<typename M1 , typename Scalar , int Options> | |
const M1 & | operator+ (const MotionBase< M1 > &v, const MotionZeroTpl< Scalar, Options > &) |
template<typename S1 , int O1, int axis, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionHelicalTpl< S1, O1, axis > &m1, const MotionDense< MotionDerived > &m2) |
template<typename S1 , int O1, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionHelicalUnalignedTpl< 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 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, int axis, typename MotionDerived > | |
MotionDerived::MotionPlain | operator+ (const MotionRevoluteTpl< S1, O1, axis > &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 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 MotionTranslationTpl< S1, O1 > &m1, const MotionDense< MotionDerived > &m2) |
template<typename Scalar , int Options, typename M1 > | |
const M1 & | operator+ (const MotionZeroTpl< Scalar, Options > &, const MotionBase< M1 > &v) |
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 JointDataCompositeTpl< Scalar, Options, JointCollectionTpl > &jdata) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
std::ostream & | operator<< (std::ostream &os, const JointModelCompositeTpl< Scalar, Options, JointCollectionTpl > &jmodel) |
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 ConstraintDataDerived , typename Scalar , int Options, template< typename S, int O > class ConstraintCollectionTpl> | |
bool | operator== (const ConstraintDataBase< ConstraintDataDerived > &data1, const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &data2) |
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 M1 , typename F1 > | |
traits< F1 >::ForcePlain | operator^ (const MotionDense< M1 > &v, const ForceBase< F1 > &f) |
template<typename M1 , typename M2 > | |
traits< M1 >::MotionPlain | operator^ (const MotionDense< M1 > &v1, const MotionDense< M2 > &v2) |
Basic operations specialization. More... | |
template<typename MotionDerived , typename S2 , int O2, int axis> | |
EIGEN_STRONG_INLINE MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionHelicalTpl< S2, O2, axis > &m2) |
template<typename MotionDerived , typename S2 , int O2> | |
EIGEN_STRONG_INLINE MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &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, 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, 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 MotionRevoluteUnalignedTpl< S2, O2 > &m2) |
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> | |
MotionDerived::MotionPlain | operator^ (const MotionDense< MotionDerived > &m1, const MotionTranslationTpl< S2, O2 > &m2) |
template<typename MatrixType , typename VectorType > | |
void | orthonormalisation (const Eigen::MatrixBase< MatrixType > &basis, const Eigen::MatrixBase< VectorType > &vec_) |
Perform the Gram-Schmidt orthonormalisation on the input/output vector for a given input basis. More... | |
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 (ABA) | |
PINOCCHIO_DEFINE_ALGO_CHECKER (CRBA) | |
PINOCCHIO_DEFINE_ALGO_CHECKER (Parent) | |
Simple model checker, that assert that model.parents is indeed a tree. More... | |
PINOCCHIO_DEFINE_COMPARISON_OP (equal_to_op,==) | |
PINOCCHIO_DEFINE_COMPARISON_OP (greater_than_op, >) | |
PINOCCHIO_DEFINE_COMPARISON_OP (greater_than_or_equal_to_op, >=) | |
PINOCCHIO_DEFINE_COMPARISON_OP (less_than_op,<) | |
PINOCCHIO_DEFINE_COMPARISON_OP (less_than_or_equal_to_op,<=) | |
PINOCCHIO_DEFINE_COMPARISON_OP (not_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 Motion1 , typename Motion2 > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (typename Motion2::Vector3) classicAcceleration(const MotionDense< Motion1 > &spatial_velocity | |
Computes the classic acceleration from a given spatial velocity and spatial acceleration. More... | |
template<typename Motion1 , typename Motion2 , typename SE3Scalar , int SE3Options> | |
PINOCCHIO_EIGEN_PLAIN_TYPE (typename Motion2::Vector3) classicAcceleration(const MotionDense< Motion1 > &spatial_velocity | |
Computes the classic acceleration of a given frame B knowing the spatial velocity and spatial acceleration of a frame A and the relative placement between these two frames. More... | |
template<typename Matrix6Like , typename S2 , int O2> | |
PINOCCHIO_EIGEN_REF_CONST_TYPE (Matrix6Like) operator*(const Eigen | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelFreeFlyerTpl) | |
Free-flyer joint in . More... | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelHelicalUnalignedTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelPlanarTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelPrismaticUnalignedTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelRevoluteUnalignedTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelRevoluteUnboundedUnalignedTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelSphericalTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelSphericalZYXTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelTranslationTpl) | |
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION (JointModelUniversalTpl) | |
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 Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 , class ContactModelAllocator , class ContactDataAllocator > | |
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & | pv (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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ContactModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ContactDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings) |
The Popov-Vereshchagin algorithm. It computes constrained forward dynamics, aka the joint accelerations and constraint forces given the current state, actuation and the constraints on the system. All the quantities are expressed in the LOCAL coordinate systems of the joint frames. 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) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | randomConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | randomConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | randomConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | randomConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | randomConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | randomConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
std::string | randomStringGenerator (const int len) |
Generate a random string composed of alphanumeric symbols of a given length. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | reachableWorkspace (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q0, const double time_horizon, const int frame_id, Eigen::MatrixXd &vertex, const ReachableSetParams ¶ms=ReachableSetParams()) |
Computes the reachable workspace on a fixed time horizon. For more information, please see https://gitlab.inria.fr/auctus-team/people/antunskuric/pycapacity. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
void | reachableWorkspaceHull (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q0, const double time_horizon, const int frame_id, ReachableSetResults &res, const ReachableSetParams ¶ms=ReachableSetParams()) |
Computes the convex Hull reachable workspace on a fixed time horizon. For more information, please see https://gitlab.inria.fr/auctus-team/people/antunskuric/pycapacity. More... | |
bool | replace (std::string &input_str, const std::string &from, const std::string &to) |
Replace string from with to in input_str. More... | |
template<typename VectorLike > | |
VectorLike::Scalar | retrieveLargestEigenvalue (const Eigen::MatrixBase< VectorLike > &eigenvector) |
Compute the lagest eigenvalue of a given matrix. This is taking the eigenvector computed by the function computeLargestEigenvector. 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 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... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorPool , typename TangentVectorPool1 , typename TangentVectorPool2 , typename TangentVectorPool3 > | |
void | rneaInParallel (const size_t 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... | |
PINOCCHIO_PARSERS_DLLAPI std::vector< std::string > | rosPaths () |
Parse the environment variables ROS_PACKAGE_PATH / AMENT_PREFIX_PATH and extract paths. More... | |
template<typename To , typename From > | |
To | scalar_cast (const From &value) |
void | set_default_omp_options (const size_t num_threads=(size_t) omp_get_max_threads()) |
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 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 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 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 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 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) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | squaredDistance< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | squaredDistance< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs | squaredDistance< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | squaredDistance< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | squaredDistanceSum< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar | squaredDistanceSum< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > (const context::Model &, const Eigen::MatrixBase< context::VectorXs > &, const Eigen::MatrixBase< context::VectorXs > &) |
template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | |
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > | stu_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) |
Visit a JointDataTpl through JointStUInertiaVisitor to get St*I*S matrix of the inertia matrix decomposition. More... | |
template<typename Derived > | |
void | toCSVfile (const std::string &filename, const Eigen::MatrixBase< Derived > &matrix) |
template<typename Scalar > | |
hpp::fcl::Transform3f | toFclTransform3f (const SE3Tpl< Scalar > &m) |
SE3 | toPinocchioSE3 (const hpp::fcl::Transform3f &tf) |
template<typename Vector3 , typename Scalar , typename Matrix3 > | |
void | toRotationMatrix (const Eigen::MatrixBase< Vector3 > &axis, const Scalar &angle, const Eigen::MatrixBase< Matrix3 > &res) |
Computes a rotation matrix from a vector and the angular value orientations values. More... | |
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<Eigen::UpLoType info, typename LhsMatrix , typename RhsMatrix , typename ResMat > | |
void | triangularMatrixMatrixProduct (const Eigen::MatrixBase< LhsMatrix > &lhs_mat, const Eigen::MatrixBase< RhsMatrix > &rhs_mat, const Eigen::MatrixBase< ResMat > &res) |
Evaluate the product of a triangular matrix times a matrix. Eigen showing a bug at this level, in the case of vector entry. 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 > | |
Eigen::Matrix< typename 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 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 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 const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI SE3Tpl< context::Scalar, context::Options > & | updateFramePlacement< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &, const FrameIndex) |
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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | updateFramePlacements< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
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, 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 PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | updateGeometryPlacements< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, const context::Data &, const GeometryModel &, GeometryData &) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | updateGeometryPlacements< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > (const context::Model &, context::Data &, const GeometryModel &, GeometryData &, const Eigen::MatrixBase< context::VectorXs > &) |
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... | |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void | updateGlobalPlacements< context::Scalar, context::Options, JointCollectionDefaultTpl > (const context::Model &, context::Data &) |
Variables | |
const int | Dynamic = -1 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t | Index |
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & | placement |
ReturnType | res |
const MotionDense< Motion2 > & | spatial_acceleration |
submodules = inspect.getmembers(pinocchio_pywrap_default, 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 LieGroup_t , 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 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_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.
Be carefull to include this header after fwd.hpp. fwd.hpp contains some define to change the boost::variant max size. If we don't include it before, default size is choosed that can make all the build fail.
typedef SpatialAxis<0> pinocchio::AxisVX |
Definition at line 146 of file spatial-axis.hpp.
typedef SpatialAxis<1> pinocchio::AxisVY |
Definition at line 147 of file spatial-axis.hpp.
typedef SpatialAxis<2> pinocchio::AxisVZ |
Definition at line 148 of file spatial-axis.hpp.
typedef SpatialAxis<3> pinocchio::AxisWX |
Definition at line 150 of file spatial-axis.hpp.
typedef SpatialAxis<4> pinocchio::AxisWY |
Definition at line 151 of file spatial-axis.hpp.
typedef SpatialAxis<5> pinocchio::AxisWZ |
Definition at line 152 of file spatial-axis.hpp.
typedef XAxis pinocchio::AxisX |
Definition at line 171 of file cartesian-axis.hpp.
typedef YAxis pinocchio::AxisY |
Definition at line 174 of file cartesian-axis.hpp.
typedef ZAxis pinocchio::AxisZ |
Definition at line 177 of file cartesian-axis.hpp.
using pinocchio::BroadPhaseManagerPool = typedef BroadPhaseManagerPoolTpl<ManagerDerived, Scalar> |
Definition at line 35 of file collision/pool/fwd.hpp.
using pinocchio::BroadPhaseManagerPoolTpl = typedef BroadPhaseManagerPoolBase< BroadPhaseManagerTpl<ManagerDerived>, Scalar, Options, JointCollectionTpl> |
Definition at line 32 of file collision/pool/fwd.hpp.
typedef CartesianProductOperationVariantTpl< context::Scalar, context::Options, LieGroupCollectionDefaultTpl> pinocchio::CartesianProductOperationVariant |
Definition at line 20 of file cartesian-product-variant.hpp.
Definition at line 34 of file algorithm/constraints/fwd.hpp.
typedef ConstraintDataTpl<context::Scalar, context::Options, ConstraintCollectionTpl> pinocchio::ConstraintData |
Definition at line 42 of file algorithm/constraints/fwd.hpp.
typedef ConstraintModelTpl<context::Scalar, context::Options, ConstraintCollectionTpl> pinocchio::ConstraintModel |
Definition at line 37 of file algorithm/constraints/fwd.hpp.
typedef ContactCholeskyDecompositionTpl<context::Scalar, context::Options> pinocchio::ContactCholeskyDecomposition |
Definition at line 17 of file algorithm/fwd.hpp.
typedef ContactCholeskyDecompositionAccessorTpl<double, 0> pinocchio::ContactCholeskyDecompositionAccessor |
Definition at line 53 of file delassus.cpp.
Definition at line 47 of file algorithm/constraints/fwd.hpp.
typedef DelassusOperatorDenseTpl<context::Scalar, context::Options> pinocchio::DelassusOperatorDense |
Definition at line 30 of file algorithm/fwd.hpp.
typedef DelassusOperatorSparseTpl<context::Scalar, context::Options> pinocchio::DelassusOperatorSparse |
Definition at line 36 of file algorithm/fwd.hpp.
Definition at line 51 of file algorithm/constraints/fwd.hpp.
Definition at line 197 of file force-set.hpp.
typedef boost::variant<GeometryNoMaterial, GeometryPhongMaterial> pinocchio::GeometryMaterial |
Definition at line 73 of file multibody/geometry-object.hpp.
Definition at line 24 of file multibody/pool/fwd.hpp.
typedef JointTpl<context::Scalar> pinocchio::Joint |
Definition at line 22 of file joint-generic.hpp.
Definition at line 959 of file joint-helical.hpp.
Definition at line 963 of file joint-helical.hpp.
Definition at line 967 of file joint-helical.hpp.
Definition at line 776 of file joint-prismatic.hpp.
Definition at line 780 of file joint-prismatic.hpp.
Definition at line 784 of file joint-prismatic.hpp.
typedef JointDataRevoluteUnboundedTpl<context::Scalar, context::Options, 0> pinocchio::JointDataRUBX |
Definition at line 263 of file joint-revolute-unbounded.hpp.
typedef JointDataRevoluteUnboundedTpl<context::Scalar, context::Options, 1> pinocchio::JointDataRUBY |
Definition at line 267 of file joint-revolute-unbounded.hpp.
typedef JointDataRevoluteUnboundedTpl<context::Scalar, context::Options, 2> pinocchio::JointDataRUBZ |
Definition at line 271 of file joint-revolute-unbounded.hpp.
Definition at line 872 of file joint-revolute.hpp.
Definition at line 876 of file joint-revolute.hpp.
Definition at line 880 of file joint-revolute.hpp.
Definition at line 206 of file joint-collection.hpp.
typedef JointHelicalTpl<context::Scalar, context::Options, 0> pinocchio::JointHX |
Definition at line 958 of file joint-helical.hpp.
typedef JointHelicalTpl<context::Scalar, context::Options, 1> pinocchio::JointHY |
Definition at line 962 of file joint-helical.hpp.
typedef JointHelicalTpl<context::Scalar, context::Options, 2> pinocchio::JointHZ |
Definition at line 966 of file joint-helical.hpp.
Definition at line 960 of file joint-helical.hpp.
Definition at line 964 of file joint-helical.hpp.
Definition at line 968 of file joint-helical.hpp.
Definition at line 777 of file joint-prismatic.hpp.
Definition at line 781 of file joint-prismatic.hpp.
Definition at line 785 of file joint-prismatic.hpp.
typedef JointModelRevoluteUnboundedTpl<context::Scalar, context::Options, 0> pinocchio::JointModelRUBX |
Definition at line 264 of file joint-revolute-unbounded.hpp.
typedef JointModelRevoluteUnboundedTpl<context::Scalar, context::Options, 1> pinocchio::JointModelRUBY |
Definition at line 268 of file joint-revolute-unbounded.hpp.
typedef JointModelRevoluteUnboundedTpl<context::Scalar, context::Options, 2> pinocchio::JointModelRUBZ |
Definition at line 272 of file joint-revolute-unbounded.hpp.
Definition at line 873 of file joint-revolute.hpp.
Definition at line 877 of file joint-revolute.hpp.
Definition at line 881 of file joint-revolute.hpp.
Definition at line 205 of file joint-collection.hpp.
typedef JointMotionSubspaceTpl<1, context::Scalar, context::Options> pinocchio::JointMotionSubspace1d |
Definition at line 14 of file joint-motion-subspace.hpp.
typedef JointMotionSubspaceTpl<3, context::Scalar, context::Options> pinocchio::JointMotionSubspace3d |
Definition at line 17 of file joint-motion-subspace.hpp.
typedef JointMotionSubspaceTpl<6, context::Scalar, context::Options> pinocchio::JointMotionSubspace6d |
Definition at line 18 of file joint-motion-subspace.hpp.
typedef JointMotionSubspaceTpl<Eigen::Dynamic, context::Scalar, context::Options> pinocchio::JointMotionSubspaceXd |
Definition at line 20 of file joint-motion-subspace.hpp.
Definition at line 775 of file joint-prismatic.hpp.
Definition at line 779 of file joint-prismatic.hpp.
Definition at line 783 of file joint-prismatic.hpp.
Definition at line 262 of file joint-revolute-unbounded.hpp.
Definition at line 266 of file joint-revolute-unbounded.hpp.
Definition at line 270 of file joint-revolute-unbounded.hpp.
Definition at line 871 of file joint-revolute.hpp.
Definition at line 875 of file joint-revolute.hpp.
Definition at line 879 of file joint-revolute.hpp.
Definition at line 38 of file liegroup-collection.hpp.
Definition at line 17 of file multibody/pool/fwd.hpp.
Definition at line 20 of file joint-planar.hpp.
Definition at line 20 of file joint-prismatic-unaligned.hpp.
Definition at line 21 of file joint-revolute-unaligned.hpp.
Definition at line 20 of file joint-spherical.hpp.
Definition at line 19 of file joint-translation.hpp.
Definition at line 13 of file algorithm/fwd.hpp.
Definition at line 27 of file algorithm/fwd.hpp.
Definition at line 24 of file algorithm/fwd.hpp.
using pinocchio::TreeBroadPhaseManagerPool = typedef TreeBroadPhaseManagerPoolTpl<ManagerDerived, Scalar> |
Definition at line 52 of file collision/pool/fwd.hpp.
using pinocchio::TreeBroadPhaseManagerPoolTpl = typedef BroadPhaseManagerPoolBase< TreeBroadPhaseManagerTpl<ManagerDerived>, Scalar, Options, JointCollectionTpl> |
Definition at line 49 of file collision/pool/fwd.hpp.
typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> pinocchio::VectorXb |
typedef CartesianAxis<0> pinocchio::XAxis |
Definition at line 170 of file cartesian-axis.hpp.
typedef CartesianAxis<1> pinocchio::YAxis |
Definition at line 173 of file cartesian-axis.hpp.
typedef CartesianAxis<2> pinocchio::ZAxis |
Definition at line 176 of file cartesian-axis.hpp.
anonymous enum |
Enumerator | |
---|---|
SELF |
Definition at line 17 of file liegroup-base.hpp.
anonymous enum |
Enumerator | |
---|---|
MAX_JOINT_NV |
Definition at line 14 of file multibody/joint/fwd.hpp.
Type of contact
Enumerator | |
---|---|
CONTACT_3D | |
CONTACT_6D | Point contact model. |
CONTACT_UNDEFINED |
Frame contact model The default contact is undefined |
Definition at line 19 of file algorithm/contact-info.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 31 of file multibody/frame.hpp.
Enumerator | |
---|---|
VISUAL | |
COLLISION |
Definition at line 24 of file multibody/geometry-object.hpp.
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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, | ||
const Convention | rf = Convention::LOCAL |
||
) |
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given the current state and actuation of the model 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 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) |
[in] | convention | Convention to use. |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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 Convention | convention = Convention::LOCAL |
||
) |
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). |
[in] | convention | Convention to use. |
void pinocchio::abaInParallel | ( | const size_t | 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 40 of file algorithm/parallel/aba.hpp.
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 |
|
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. |
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 |
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 |
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. |
The order of the joints in the output models are
Definition at line 51 of file algorithm/model.hpp.
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. |
The order of the joints in the output models are
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] | geomModelA | the parent geometry model. |
[in] | geomModelB | the child geometry 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. |
[out] | geomModel | the resulting geometry model. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Model pinocchio::appendModel< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Model & | , | ||
const | FrameIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::appendModel< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Model & | , | ||
const | FrameIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
context::Model & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::appendModel< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Model & | , | ||
const GeometryModel & | , | ||
const GeometryModel & | , | ||
const | FrameIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
context::Model & | , | ||
GeometryModel & | |||
) |
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 52 of file file-explorer.cpp.
|
inline |
|
inline |
Definition at line 22 of file axis-label.hpp.
|
inline |
Definition at line 27 of file axis-label.hpp.
|
inline |
Definition at line 32 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 |
|
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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType pinocchio::bodyRegressor< context::Motion, context::Motion > | ( | const MotionDense< context::Motion > & | , |
const MotionDense< context::Motion > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::bodyRegressor< context::Motion, context::Motion, context::BodyRegressorType > | ( | const MotionDense< context::Motion > & | , |
const MotionDense< context::Motion > & | , | ||
const Eigen::MatrixBase< context::BodyRegressorType > & | |||
) |
void pinocchio::buildAllJointsModel | ( | Model & | model | ) |
Definition at line 31 of file model-generator.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. |
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 134 of file algorithm/model.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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::buildReducedModel< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const GeometryModel & | , | ||
const std::vector< JointIndex > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
context::Model & | , | ||
GeometryModel & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Model pinocchio::buildReducedModel< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const std::vector< JointIndex > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::buildReducedModel< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const std::vector< JointIndex > | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
context::Model & | |||
) |
void pinocchio::calc | ( | const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > & | cmodel, |
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > & | cdata, | ||
const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | ||
const DataTpl< Scalar, Options, JointCollectionTpl > & | data | ||
) |
Definition at line 155 of file constraint-model-visitor.hpp.
|
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] | armature | Armature related to the current joint. |
[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. |
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] | v | The full model's (in which the joint belongs to) velocity vector |
|
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 | ) |
Definition at line 13 of file utils/cast.hpp.
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::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.
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). |
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 194 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 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).
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Vector3& pinocchio::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).
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Vector3& pinocchio::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).
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. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Vector3& pinocchio::centerOfMass< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
const bool | computeSubtreeComs | ||
) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Vector3& pinocchio::centerOfMass< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
KinematicLevel | , | ||
const bool | computeSubtreeComs | ||
) |
ForceIn::ForcePlain pinocchio::changeReferenceFrame | ( | const SE3Tpl< Scalar, Options > & | placement, |
const ForceDense< ForceIn > & | f_in, | ||
const ReferenceFrame | rf_in, | ||
const ReferenceFrame | rf_out | ||
) |
Definition at line 90 of file algorithm/utils/force.hpp.
void pinocchio::changeReferenceFrame | ( | const SE3Tpl< Scalar, Options > & | placement, |
const ForceDense< ForceIn > & | f_in, | ||
const ReferenceFrame | rf_in, | ||
const ReferenceFrame | rf_out, | ||
ForceDense< ForceOut > & | f_out | ||
) |
[out] f_out Resulting force quantity.
Definition at line 19 of file algorithm/utils/force.hpp.
MotionIn::MotionPlain pinocchio::changeReferenceFrame | ( | const SE3Tpl< Scalar, Options > & | placement, |
const MotionDense< MotionIn > & | m_in, | ||
const ReferenceFrame | rf_in, | ||
const ReferenceFrame | rf_out | ||
) |
Definition at line 91 of file algorithm/utils/motion.hpp.
void pinocchio::changeReferenceFrame | ( | const SE3Tpl< Scalar, Options > & | placement, |
const MotionDense< MotionIn > & | m_in, | ||
const ReferenceFrame | rf_in, | ||
const ReferenceFrame | rf_out, | ||
MotionDense< MotionOut > & | m_out | ||
) |
[out] m_out Resulting motion quantity.
Definition at line 20 of file algorithm/utils/motion.hpp.
bool pinocchio::check_expression_if_real | ( | const Any & | expression | ) |
Definition at line 35 of file utils/check.hpp.
bool pinocchio::check_expression_if_real | ( | const Any & | expression | ) |
Definition at line 41 of file utils/check.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 40 of file utils/version.hpp.
|
inline |
Computes the classic acceleration from a given spatial velocity and spatial acceleration.
Motion1 | type of the input spatial velocity. |
Motion2 | type of the input spatial acceleration. |
Vector3Like | type of the return type (a type similar to a 3D vector). |
[in] | spatial_velocity | input spatial velocity. |
[in] | spatial_acceleration | input spatial acceleration. |
[out] | res | computed classic acceleration. |
Definition at line 29 of file spatial/classic-acceleration.hpp.
|
inline |
Computes the classic acceleration of a given frame B knowing the spatial velocity and spatial acceleration of a frame A and the relative placement between these two frames.
Motion1 | type of the input spatial velocity. |
Motion2 | type of the input spatial acceleration. |
SE3Scalar | Scalar type of the SE3 object. |
SE3Options | Options of the SE3 object. |
Vector3Like | type of the return type (a type similar to a 3D vector). |
[in] | spatial_velocity | input spatial velocity. |
[in] | spatial_acceleration | input spatial acceleration. |
[in] | placement | relative placement betwen the frame A and the frame B. |
[out] | res | computed classic acceleration. |
Definition at line 84 of file spatial/classic-acceleration.hpp.
pinocchio::classicAcceleration | ( | spatial_velocity | , |
spatial_acceleration | , | ||
placement | , | ||
res | |||
) |
pinocchio::classicAcceleration | ( | spatial_velocity | , |
spatial_acceleration | , | ||
res | |||
) |
bool pinocchio::compare_shared_ptr | ( | const std::shared_ptr< T > & | ptr1, |
const std::shared_ptr< T > & | ptr2 | ||
) |
Compares two std::shared_ptr.
Definition at line 16 of file shared-ptr.hpp.
void pinocchio::computeABADerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data | ||
) |
The derivatives of the Articulated-Body algorithm. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden.
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. |
void pinocchio::computeABADerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const container::aligned_vector< ForceTpl< Scalar, Options >> & | fext | ||
) |
The derivatives of the Articulated-Body algorithm with external forces. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden.
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] | fext | External forces expressed in the local frame of the joints (dim model.njoints). |
void pinocchio::computeABADerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
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. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden.
JointCollection | Collection of Joint types. |
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] | 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. |
std::enable_if< ConfigVectorType::IsVectorAtCompileTime || TangentVectorType1::IsVectorAtCompileTime || TangentVectorType2::IsVectorAtCompileTime, void>::type pinocchio::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.
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). |
void pinocchio::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.
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). |
void pinocchio::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.
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. |
void pinocchio::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.
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. |
std::enable_if< !(MatrixType1::IsVectorAtCompileTime || MatrixType2::IsVectorAtCompileTime || MatrixType3::IsVectorAtCompileTime), void>::type pinocchio::computeABADerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
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. This function exploits the internal computations made in pinocchio::aba to significantly reduced the computation burden.
JointCollection | Collection of Joint types. |
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. |
[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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeABADerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeABADerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
const container::aligned_vector< ForceTpl< context::Scalar, context::Options >> & | |||
) |
void pinocchio::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:
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::computeBodyRadius | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const GeometryModel & | geom_model, | ||
GeometryData & | geom_data | ||
) |
template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeBodyRadius< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const GeometryModel & | , | ||
GeometryData & | |||
) |
void pinocchio::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.
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). |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::computeCentroidalMap | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q | ||
) |
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). |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::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.
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). |
const DataTpl<Scalar, Options, JointCollectionTpl>::Force& pinocchio::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.
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Force& pinocchio::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.
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). |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI ForceTpl<context::Scalar, context::Options>& pinocchio::computeCentroidalMomentum< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::Force& pinocchio::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.
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Force& pinocchio::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.
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). |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI ForceTpl<context::Scalar, context::Options>& pinocchio::computeCentroidalMomentumTimeVariation< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
bool pinocchio::computeCollision | ( | const GeometryModel & | geom_model, |
GeometryData & | geom_data, | ||
const PairIndex | pair_id | ||
) |
Compute the collision status between a SINGLE collision pair. The result is store in the collisionResults vector.
[in] | GeomModel | the geometry model (const) |
[out] | GeomData | the corresponding geometry data, where computations are done. |
[in] | pair_id | The collsion pair index in the GeometryModel. |
bool pinocchio::computeCollision | ( | const GeometryModel & | geom_model, |
GeometryData & | geom_data, | ||
const PairIndex | pair_id, | ||
fcl::CollisionRequest & | collision_request | ||
) |
Compute the collision status between a SINGLE collision pair. The result is store in the collisionResults vector.
[in] | GeomModel | the geometry model (const) |
[out] | GeomData | the corresponding geometry data, where computations are done. |
[in] | pair_id | The collsion pair index in the GeometryModel. |
[in] | collision_request | The collision request associated to the collision pair. |
bool pinocchio::computeCollisions | ( | BroadPhaseManagerBase< BroadPhaseManagerDerived > & | broadphase_manager, |
CollisionCallBackBase * | callback | ||
) |
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeometryPlacements and broadphase_manager.update() have been called first.
[in] | broadphase_manager | broadphase instance for collision detection. |
[in] | callback | callback pointer used for collision detection. |
[in] | stopAtFirstCollision | if true, stop the loop over the collision pairs when the first collision is detected. |
Definition at line 34 of file broadphase.hpp.
bool pinocchio::computeCollisions | ( | BroadPhaseManagerBase< BroadPhaseManagerDerived > & | broadphase_manager, |
const bool | stopAtFirstCollision = false |
||
) |
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeometryPlacements and broadphase_manager.update() have been called first.
[in] | broadphase_manager | broadphase instance for collision detection. |
[in] | stopAtFirstCollision | if true, stop the loop over the collision pairs when the first collision is detected. |
Definition at line 57 of file broadphase.hpp.
bool pinocchio::computeCollisions | ( | const GeometryModel & | geom_model, |
GeometryData & | geom_data, | ||
const bool | stopAtFirstCollision = false |
||
) |
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeometryPlacements has been called first.
[in] | geom_model | geometry model (const) |
[out] | geom_data | corresponding geometry data (nonconst) where collisions are computed |
[in] | stopAtFirstCollision | if true, stop the loop over the collision pairs when the first collision is detected. |
|
inline |
Compute the forward kinematics, update the geometry placements and run the collision detection using the broadphase manager.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | robot model (const) |
[out] | data | corresponding data (nonconst) where the forward kinematics results are stored |
[in] | broadphase_manager | broadphase manager for collision detection. |
[in] | callback | callback pointer used for collision detection./// |
[in] | q | robot configuration. |
[in] | stopAtFirstCollision | if true, stop the loop over the collision pairs when the first collision is detected. |
Definition at line 94 of file broadphase.hpp.
|
inline |
Compute the forward kinematics, update the geometry placements and run the collision detection using the broadphase manager.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | robot model (const) |
[out] | data | corresponding data (nonconst) where the forward kinematics results are stored |
[in] | broadphase_manager | broadphase manager for collision detection. |
[in] | q | robot configuration. |
[in] | stopAtFirstCollision | if true, stop the loop over the collision pairs when the first collision is detected. |
Definition at line 133 of file broadphase.hpp.
bool pinocchio::computeCollisions | ( | 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 |
||
) |
Compute the forward kinematics, update the geometry placements and calls computeCollision for every active pairs of GeometryData.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | robot model (const) |
[out] | data | corresponding data (nonconst) where the forward kinematics results are stored |
[in] | geom_model | geometry model (const) |
[out] | geom_data | corresponding geometry data (nonconst) where distances are computed |
[in] | q | robot configuration. |
[in] | stopAtFirstCollision | if true, stop the loop over the collision pairs when the first collision is detected. |
template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool pinocchio::computeCollisions< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const GeometryModel & | , | ||
GeometryData & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const bool | stopAtFirstCollision | ||
) |
void pinocchio::computeCollisionsInParallel | ( | const size_t | num_threads, |
BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > & | pool, | ||
const Eigen::MatrixBase< ConfigVectorPool > & | q, | ||
const Eigen::MatrixBase< CollisionVectorResult > & | res, | ||
const bool | stopAtFirstCollisionInConfiguration = false , |
||
const bool | stopAtFirstCollisionInBatch = false |
||
) |
Definition at line 25 of file parallel/broadphase.hpp.
void pinocchio::computeCollisionsInParallel | ( | const size_t | num_threads, |
BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > & | pool, | ||
const std::vector< Eigen::MatrixXd > & | trajectories, | ||
std::vector< VectorXb > & | res, | ||
const bool | stopAtFirstCollisionInTrajectory = false |
||
) |
Evaluate the collision over a set of trajectories and return whether a trajectory contains a collision.
Definition at line 104 of file parallel/broadphase.hpp.
|
inline |
Definition at line 18 of file collision/parallel/geometry.hpp.
bool pinocchio::computeCollisionsInParallel | ( | const size_t | 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 67 of file collision/parallel/geometry.hpp.
void pinocchio::computeCollisionsInParallel | ( | const size_t | num_threads, |
GeometryPoolTpl< Scalar, Options, JointCollectionTpl > & | pool, | ||
const Eigen::MatrixBase< ConfigVectorPool > & | q, | ||
const Eigen::MatrixBase< CollisionVectorResult > & | res, | ||
const bool | stopAtFirstCollisionInConfiguration = false , |
||
const bool | stopAtFirstCollisionInBatch = false |
||
) |
Definition at line 86 of file collision/parallel/geometry.hpp.
|
inline |
Definition at line 102 of file constrained-dynamics-derivatives.hpp.
|
inline |
Definition at line 54 of file constrained-dynamics-derivatives.hpp.
|
inline |
Definition at line 82 of file constrained-dynamics-derivatives.hpp.
|
inline |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | , | ||
const ProximalSettingsTpl< context::Scalar > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs > | ( | const context::Model & | , |
context::Data & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeConstraintDynamicsDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs, context::MatrixXs > | ( | const context::Model & | , |
context::Data & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | , | ||
const ProximalSettingsTpl< context::Scalar > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>:: TangentVectorType& pinocchio::computeContactImpulses | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< VectorLikeC > & | c_ref, | ||
const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > & | contact_models, | ||
std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > & | contact_datas, | ||
const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > & | cones, | ||
const Eigen::MatrixBase< VectorLikeR > & | R, | ||
const Eigen::MatrixBase< VectorLikeGamma > & | constraint_correction, | ||
ProximalSettingsTpl< Scalar > & | settings, | ||
const boost::optional< VectorLikeImp > & | impulse_guess = boost::none |
||
) |
Compute the contact impulses given a target velocity of contact points.
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] | c_ref | The contact point velocity |
[in] | contact_models | The list of contact models. |
[in] | contact_datas | The list of contact_datas. |
[in] | cones | list of friction cones. |
[in] | R | vector representing the diagonal of the compliance matrix. |
[in] | constraint_correction | vector representing the constraint correction. |
[in] | settings | The settings for the proximal algorithm. |
[in] | impulse_guess | initial guess for the contact impulses. |
Definition at line 56 of file contact-inverse-dynamics.hpp.
const DataTpl<Scalar, Options, JointCollectionTpl>::MatrixXs& pinocchio::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:
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::computeDampedDelassusMatrixInverse | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > & | contact_models, | ||
std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > & | contact_data, | ||
const Eigen::MatrixBase< MatrixType > & | damped_delassus_inverse, | ||
const Scalar | mu, | ||
const bool | scaled = false , |
||
const bool | Pv = true |
||
) |
Computes the inverse of the Delassus matrix associated to a set of given constraints.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
ModelAllocator | Allocator class for the std::vector. |
DataAllocator | Allocator class for the std::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 (size model.nq). |
[in] | contact_models | Vector of contact models. |
[in] | contact_datas | Vector of contact data. |
[out] | damped_delassus_inverse | The resulting damped Delassus matrix. |
[in] | mu | Damping factor well-posdnessed of the problem. |
[in] | scaled | If set to true, the solution is scaled my a factor to avoid numerical rounding issues. |
[in] | Pv | If set to true, uses PV-OSIMr, otherwise uses EFPA. |
void pinocchio::computeDelassusMatrix | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > & | contact_models, | ||
std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > & | contact_data, | ||
const Eigen::MatrixBase< MatrixType > & | delassus, | ||
const Scalar | mu = 0 |
||
) |
Computes the Delassus matrix associated to a set of given constraints.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
ModelAllocator | Allocator class for the std::vector. |
DataAllocator | Allocator class for the std::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 (size model.nq). |
[in] | contact_models | Vector of contact models. |
[in] | contact_datas | Vector of contact data. |
[out] | delassus | The resulting Delassus matrix. |
[in] | mu | Optional damping factor used when computing the inverse of the Delassus matrix. |
fcl::DistanceResult& pinocchio::computeDistance | ( | const GeometryModel & | geom_model, |
GeometryData & | geom_data, | ||
const PairIndex | pair_id | ||
) |
Compute the minimal distance between collision objects of a SINGLE collison pair.
[in] | GeomModel | the geometry model (const) |
[out] | GeomData | the corresponding geometry data, where computations are done. |
[in] | pair_id | The index of the collision pair in geom model. |
std::size_t pinocchio::computeDistances | ( | const GeometryModel & | geom_model, |
GeometryData & | geom_data | ||
) |
Compute the minimal distance between collision objects of a ALL collison pair.
[in] | GeomModel | the geometry model (const) |
[out] | GeomData | the corresponding geometry data, where computations are done. |
std::size_t pinocchio::computeDistances | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const GeometryModel & | geom_model, | ||
GeometryData & | geom_data | ||
) |
Update the geometry placements and calls computeDistance for every active pairs of GeometryData.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | robot model (const) |
[in] | data | corresponding data (nonconst) where FK results are stored |
[in] | geom_model | geometry model (const) |
[out] | geom_data | corresponding geometry data (nonconst) where distances are computed |
std::size_t pinocchio::computeDistances | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const GeometryModel & | geom_model, | ||
GeometryData & | geom_data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q | ||
) |
Compute the forward kinematics, update the geometry placements and calls computeDistance for every active pairs of GeometryData.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | robot model (const) |
[in] | data | corresponding data (nonconst) where FK results are stored |
[in] | geom_model | geometry model (const) |
[out] | geom_data | corresponding geometry data (nonconst) where distances are computed |
[in] | q | robot configuration. |
template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI std::size_t pinocchio::computeDistances< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const GeometryModel & | , | ||
GeometryData & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
void pinocchio::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.
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 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 476 of file frames.hpp.
|
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(). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const | FrameIndex, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
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 151 of file regressor.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 | ||
) |
[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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs pinocchio::computeFrameKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeFrameKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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:
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). |
void pinocchio::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.
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 |
Definition at line 44 of file impulse-dynamics-derivatives.hpp.
|
inline |
void pinocchio::computeJointJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const JointIndex | joint_id, | ||
const Eigen::MatrixBase< Matrix6Like > & | J | ||
) |
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store 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] | joint_id | 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(). |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::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.
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::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.
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). |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs& pinocchio::computeJointJacobians< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::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.
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::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.
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. |
void pinocchio::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.
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 344 of file kinematics-derivatives.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeJointKinematicHessians< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeJointKinematicHessians< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
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 102 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 | ||
) |
[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, | ||
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 52 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 SE3Tpl< Scalar, Options > & | placement, | ||
const Eigen::MatrixBase< Matrix6xReturnType > & | kinematic_regressor | ||
) |
[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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs pinocchio::computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs pinocchio::computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame, | ||
const SE3Tpl< context::Scalar, context::Options > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeJointKinematicRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
|
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). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs& pinocchio::computeJointTorqueRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
Scalar pinocchio::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.
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. |
Scalar pinocchio::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.
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). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::computeKineticEnergy< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Data::RowVectorXs& pinocchio::computeKineticEnergyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeKKTContactDynamicMatrixInverse< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::MatrixXs, context::MatrixXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const context::Scalar & | |||
) |
void pinocchio::computeLargestEigenvector | ( | const MatrixLike & | mat, |
const Eigen::PlainObjectBase< VectorLike > & | _eigenvector_est, | ||
const int | max_it = 10 , |
||
const typename MatrixLike::Scalar | rel_tol = 1e-8 |
||
) |
Compute the lagest eigenvector of a given matrix according to a given eigenvector estimate.
Definition at line 138 of file eigenvalues.hpp.
Eigen::Matrix<typename MatrixLike::Scalar, MatrixLike::RowsAtCompileTime, 1> pinocchio::computeLargestEigenvector | ( | const MatrixLike & | mat, |
const int | max_it = 10 , |
||
const typename MatrixLike::Scalar | rel_tol = 1e-8 |
||
) |
Eigen::Matrix<typename MatrixLike::Scalar, MatrixLike::RowsAtCompileTime, 1> pinocchio::computeLowestEigenvector | ( | const MatrixLike & | mat, |
const bool | compute_largest = true , |
||
const int | max_it = 10 , |
||
const typename MatrixLike::Scalar | rel_tol = 1e-8 |
||
) |
void pinocchio::computeLowestEigenvector | ( | const MatrixLike & | mat, |
const Eigen::PlainObjectBase< VectorLike1 > & | largest_eigenvector_est, | ||
const Eigen::PlainObjectBase< VectorLike2 > & | lowest_eigenvector_est, | ||
const bool | compute_largest = true , |
||
const int | max_it = 10 , |
||
const typename MatrixLike::Scalar | rel_tol = 1e-8 |
||
) |
Compute the lagest eigenvector of a given matrix according to a given eigenvector estimate.
Definition at line 168 of file eigenvalues.hpp.
Scalar pinocchio::computeMechanicalEnergy | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data | ||
) |
Computes the mechanical energy of the system stored in data.mechanical_energy. 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. |
Scalar pinocchio::computeMechanicalEnergy | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType > & | v | ||
) |
Computes the mechanical energy of the system stored in data.mechanical_energy. 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). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::computeMechanicalEnergy< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::RowMatrixXs& pinocchio::computeMinverse | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data | ||
) |
Computes the inverse of the joint space inertia matrix using Articulated Body formulation. Compared to the complete signature computeMinverse<Scalar,Options,ConfigVectorType>, this version assumes that ABA has been called first.
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::RowMatrixXs& pinocchio::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.
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). |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::RowMatrixXs& pinocchio::computeMinverse< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
Scalar pinocchio::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.
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. |
Scalar pinocchio::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.
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). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::computePotentialEnergy< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::RowVectorXs& pinocchio::computePotentialEnergyRegressor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q | ||
) |
\brief Computes the kinetic energy regressor that links the kinetic energy of the system to the dynamic parameters of each link according to the current robot motion. The result is stored in `data.kineticEnergyRegressor` and it corresponds to a matrix \f$ Y_e \f$ such that \f$ K = Y_e(q,\dot{q})\pi \f$ where \pi_i = \text{model.inertias[i].toDynamicParameters()} \f$ \tparam JointCollection Collection of Joint types. \tparam ConfigVectorType Type of the joint configuration vector. \tparam TangentVectorType Type of the joint velocity vector. \param[in] model The model structure of the rigid body system. \param[in] data The data structure of the rigid body system. \param[in] q The joint configuration vector (dim model.nq). \param[in] v The joint velocity vector (dim model.nv). \return The kinetic energy regressor of the system.
template< typename Scalar, int Options, template<typename, int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType> const typename DataTpl<Scalar, Options, JointCollectionTpl>::RowVectorXs & computeKineticEnergyRegressor( const ModelTpl<Scalar, Options, JointCollectionTpl> & model, DataTpl<Scalar, Options, JointCollectionTpl> & data, const Eigen::MatrixBase<ConfigVectorType> & q, const Eigen::MatrixBase<TangentVectorType> & v);
\brief Computes the potential energy regressor that links the potential energy of the system to the dynamic parameters of each link according to the current robot motion. The result is stored in `data.potentialEnergyRegressor` and it corresponds to a matrix \f$ Y_p \f$ such that \f$ P = Y_p(q)\pi \f$ where \pi_i = \text{model.inertias[i].toDynamicParameters()} \f$ \tparam JointCollection Collection of Joint types. \tparam ConfigVectorType Type of the joint configuration vector. \param[in] model The model structure of the rigid body system. \param[in] data The data structure of the rigid body system. \param[in] q The joint configuration vector (dim model.nq). \return The kinetic energy regressor of the system.
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Data::RowVectorXs& pinocchio::computePotentialEnergyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
void pinocchio::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.
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::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.
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). |
void pinocchio::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.
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. |
void pinocchio::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.
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 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 138 of file rnea-second-order-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 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). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix3x& pinocchio::computeStaticRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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:
. 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). |
void pinocchio::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.
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. |
void pinocchio::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.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::computeSubtreeMasses< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
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. |
Scalar pinocchio::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.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::computeTotalMass< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | ) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::computeTotalMass< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
|
inline |
The constrained Articulated Body Algorithm (constrainedABA). It computes constrained forward dynamics, aka the joint accelerations and constraint forces given the current state, actuation and the constraints on the system. All the quantities are expressed in the LOCAL coordinate systems of the joint frames.
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. |
Allocator | Allocator class for the std::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] | contact_models | Vector of contact models. |
[in] | contact_datas | Vector of contact data. |
[in] | settings | Proximal settings (mu, accuracy and maximal number of iterations). |
|
inline |
Computes the forward dynamics with contact constraints according to a given list of Contact information.
It computes the following problem:
where is the free acceleration (i.e. without constraints), is the mass matrix, the constraint Jacobian and is the constraint drift. By default, the constraint Jacobian is assumed to be full rank, and undamped Cholesky inverse is performed.
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. |
Allocator | Allocator class for the std::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 (size model.nq). |
[in] | v | The joint velocity (size model.nv). |
[in] | tau | The joint torque vector (size model.nv). |
[in] | contact_models | Vector of contact models. |
[in] | contact_datas | Vector of contact data. |
Definition at line 147 of file constrained-dynamics.hpp.
|
inline |
Computes the forward dynamics with contact constraints according to a given list of contact information.
It computes the following problem: [
where is the free acceleration (i.e. without constraints), is the mass matrix, the constraint Jacobian and is the constraint drift. By default, the constraint Jacobian is assumed to be full rank, and undamped Cholesky inverse is performed.
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. |
Allocator | Allocator class for the std::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 (size model.nq). |
[in] | v | The joint velocity (size model.nv). |
[in] | tau | The joint torque vector (size model.nv). |
[in] | contact_models | Vector of contact models. |
[in] | contact_datas | Vector of contact data. |
[in] | settings | Proximal settings (mu, accuracy and maximal number of iterations). |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs& pinocchio::constraintDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | |||
) |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs& pinocchio::constraintDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | , | ||
ProximalSettingsTpl< context::Scalar > & | |||
) |
|
inline |
Definition at line 172 of file constrained-dynamics.hpp.
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs& pinocchio::contactABA< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>:: TangentVectorType& pinocchio::contactInverseDynamics | ( | 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, | ||
Scalar | dt, | ||
const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > & | contact_models, | ||
std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > & | contact_datas, | ||
const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > & | cones, | ||
const Eigen::MatrixBase< VectorLikeR > & | R, | ||
const Eigen::MatrixBase< VectorLikeGamma > & | constraint_correction, | ||
ProximalSettingsTpl< Scalar > & | settings, | ||
const boost::optional< VectorLikeLam > & | lambda_guess = boost::none |
||
) |
The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the presence of contacts, 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). |
[in] | dt | The time step. |
[in] | contact_models | The list of contact models. |
[in] | contact_datas | The list of contact_datas. |
[in] | cones | list of friction cones. |
[in] | R | vector representing the diagonal of the compliance matrix. |
[in] | constraint_correction | vector representing the constraint correction. |
[in] | settings | The settings for the proximal algorithm. |
[in] | lambda_guess | initial guess for the contact forces. |
Definition at line 190 of file contact-inverse-dynamics.hpp.
|
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::MatrixXs& pinocchio::crba | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Convention | convention = Convention::LOCAL |
||
) |
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). |
[in] | convention | Convention to use. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs& pinocchio::crba< context::Scalar, context::Options, JointCollectionDefaultTpl, Eigen::Ref< const context::VectorXs > > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< Eigen::Ref< const context::VectorXs >> & | , | ||
const Convention | convention | ||
) |
ConstraintDataTpl<Scalar, Options, ConstraintCollectionTpl> pinocchio::createData | ( | const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > & | cmodel | ) |
Definition at line 239 of file constraint-model-visitor.hpp.
|
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 |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix6x& pinocchio::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.
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< JacobianIn_t > & | Jin, | ||
int | self, | ||
const Eigen::MatrixBase< JacobianOut_t > & | Jout, | ||
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< 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, | ||
int | self, | ||
const Eigen::MatrixBase< JacobianIn_t > & | Jin, | ||
const Eigen::MatrixBase< JacobianOut_t > & | Jout, | ||
const ArgumentPosition | arg | ||
) |
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 742 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 742 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dDifference< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dDifference< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition | ||
) |
|
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 193 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 193 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::difference< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::difference< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::difference< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::difference< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
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, | ||
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, | ||
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 | ||
) |
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 442 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 487 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. |
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 487 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dIntegrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dIntegrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition, | ||
const | AssignmentOperatorType | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dIntegrate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition, | ||
const | AssignmentOperatorType | ||
) |
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< JacobianMatrixType > & | J, | ||
const ArgumentPosition | arg | ||
) |
Transport in place a matrix from the terminal to the initial 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 to vector 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 661 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 initial 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 to vector 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 661 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 initial 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 to vector 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 576 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 initial 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 to vector 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 576 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dIntegrateTransport< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dIntegrateTransport< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::dIntegrateTransport< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::MatrixXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | , | ||
const | ArgumentPosition | ||
) |
|
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 101 of file liegroup-variant-visitors.hpp.
Scalar pinocchio::distance | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1 | ||
) |
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 846 of file joint-configuration.hpp.
Scalar pinocchio::distance | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1 | ||
) |
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 846 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::distance< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::distance< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
|
inline |
Definition at line 114 of file timings.cpp.
|
inline |
Definition at line 147 of file timings.cpp.
|
inline |
Definition at line 46 of file timings.cpp.
|
inline |
Definition at line 78 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 36 of file 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 417 of file 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 347 of file spatial/explog.hpp.
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 45 of file file-explorer.cpp.
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.
JointIndex pinocchio::findCommonAncestor | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
JointIndex | joint1_id, | ||
JointIndex | joint2_id, | ||
size_t & | index_ancestor_in_support1, | ||
size_t & | index_ancestor_in_support2 | ||
) |
Computes the common ancestor between two joints belonging to the same kinematic tree.
[in] | model | the input model. |
[in] | joint1_id | index of the first joint. |
[in] | joint2_id | index of the second joint. |
[out] | index_ancestor_in_support1 | index of the ancestor within model.support[joint1_id]. |
[out] | index_ancestor_in_support2 | index of the ancestor within model.support[joint2_id]. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex pinocchio::findCommonAncestor< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
JointIndex | , | ||
JointIndex | , | ||
size_t & | , | ||
size_t & | |||
) |
|
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. |
void pinocchio::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.
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). |
void pinocchio::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.
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::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.
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] | frame_id | The id of the frame. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType& pinocchio::frameBodyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
FrameIndex | |||
) |
|
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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::framesForwardKinematics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
MotionTpl<Scalar, Options> pinocchio::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.
[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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame | ||
) |
void pinocchio::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.
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. . |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getCenterOfMassVelocityDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix3x > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::Matrix3x > & | |||
) |
void pinocchio::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.
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] | 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). |
MotionTpl<Scalar, Options> pinocchio::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.
[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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getClassicalAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame | ||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::Vector3& pinocchio::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).
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. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Vector3& pinocchio::getComFromCrba< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
void pinocchio::getConstraintJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const RigidConstraintModelTpl< Scalar, Options > & | constraint_model, | ||
RigidConstraintDataTpl< Scalar, Options > & | constraint_data, | ||
const Eigen::MatrixBase< Matrix6Like > & | J | ||
) |
Computes the kinematic Jacobian associatied to a given constraint model.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | constraint_model | Constraint model. |
[in] | constraint_data | Constraint data. |
[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.fill(0.). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getConstraintJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::MatrixXs > | ( | const context::Model & | , |
const context::Data & | , | ||
const context::RigidConstraintModel & | , | ||
context::RigidConstraintData & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | |||
) |
void pinocchio::getConstraintsJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintDataAllocator > & | constraint_model, | ||
std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > & | constraint_data, | ||
const Eigen::MatrixBase< DynamicMatrixLike > & | J | ||
) |
Computes the kinematic Jacobian associatied to a given set of constraint models.
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | constraint_models | Vector of constraint models. |
[in] | constraint_datas | Vector of constraint data. |
[out] | J | A reference on the Jacobian matrix where the results will be stored in (dim nc x model.nv). You must fill J with zero elements, e.g. J.fill(0.). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getConstraintsJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::MatrixXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
const context::Data & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::MatrixXs& pinocchio::getCoriolisMatrix | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data | ||
) |
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. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::MatrixXs& pinocchio::getCoriolisMatrix< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
|
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 the 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. |
Definition at line 165 of file frames.hpp.
|
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] | joint_id | Id of the parent joint |
[in] | placement | frame placement with respect to the parent joint |
[in] | rf | Reference frame in which the acceleration is expressed. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getFrameAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getFrameAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame | ||
) |
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 frame spatial velocity w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
Definition at line 181 of file frames-derivatives.hpp.
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 frame spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the frame spatial velociy w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
Definition at line 309 of file frames-derivatives.hpp.
void pinocchio::getFrameAccelerationDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
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 spatial acceleration of a frame given by its relative placement, 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] | joint_id | Index of the supporting joint |
[in] | placement | Placement of the Frame w.r.t. the joint frame. |
[in] | rf | Reference frame in which the velocity is expressed. |
[out] | v_partial_dq | Partial derivative of the frame spatial velocity w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
void pinocchio::getFrameAccelerationDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
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] | joint_id | Index of the supporting joint |
[in] | placement | Placement of the Frame w.r.t. the joint frame. |
[in] | rf | Reference frame in which the velocity is expressed. |
[out] | v_partial_dq | Partial derivative of the frame spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the frame spatial velociy w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
[out] | a_partial_dq | Partial derivative of the frame spatial acceleration w.r.t. . |
Definition at line 249 of file frames-derivatives.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameAccelerationDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
|
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. |
Definition at line 225 of file frames.hpp.
|
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] | joint_id | Id of the parent joint |
[in] | placement | frame placement with respect to the parent joint |
[in] | rf | Reference frame in which the acceleration is expressed. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getFrameClassicalAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getFrameClassicalAcceleration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame | ||
) |
Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> pinocchio::getFrameJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const FrameIndex | frame_id, | ||
const ReferenceFrame | reference_frame | ||
) |
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system, in the local world aligned frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians.
JointCollection | Collection of Joint types. |
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | frame_id | Index of the frame |
[in] | reference_frame | Reference frame in which the Jacobian is expressed. |
Definition at line 394 of file frames.hpp.
|
inline |
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system, in the local world aligned frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians.
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 | Index of the frame |
[in] | reference_frame | Reference frame in which the Jacobian is expressed. |
[out] | J | The Jacobian of the Frame expressed in the coordinates Frame. |
Definition at line 348 of file frames.hpp.
Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> pinocchio::getFrameJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const ReferenceFrame | reference_frame | ||
) |
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame, and whose columns are either expressed in the LOCAL frame coordinate system, in the local world aligned frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians.
JointCollection | Collection of Joint types. |
[in] | model | The kinematic model |
[in] | data | Data associated to model |
[in] | joint_id | Index of the joint. |
[in] | reference_frame | Reference frame in which the Jacobian is expressed. |
Definition at line 302 of file frames.hpp.
void pinocchio::getFrameJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const ReferenceFrame | reference_frame, | ||
const Eigen::MatrixBase< Matrix6xLike > & | J | ||
) |
Returns the jacobian of the frame given by its relative placement w.r.t. a joint frame, and whose columns are either expressed in the LOCAL frame coordinate system, in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame or in the WORLD coordinate system, depending on the value of reference_frame. You must first call pinocchio::computeJointJacobians.
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] | joint_id | Index of the joint. |
[in] | reference_frame | Reference frame in which the Jacobian is expressed. |
[out] | J | The Jacobian of the Frame expressed in the reference_frame coordinate system. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs pinocchio::getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs pinocchio::getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
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 WORLD frame (rf = WORLD), in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame or in the LOCAL frame (rf = LOCAL).
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.). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameJacobianTimeVariation< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
|
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. |
Definition at line 107 of file frames.hpp.
|
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] | joint_id | Id of the parent joint |
[in] | placement | frame placement with respect to the parent joint |
[in] | rf | Reference frame in which the velocity is expressed. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getFrameVelocity< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getFrameVelocity< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame | ||
) |
void pinocchio::getFrameVelocityDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix6xOut1 > & | v_partial_dq, | ||
const Eigen::MatrixBase< Matrix6xOut2 > & | v_partial_dv | ||
) |
Computes the partial derivatives of the spatial velocity of a frame given by its relative placement, 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] | joint_id | Index of the supporting joint |
[in] | placement | Placement of the Frame w.r.t. the joint frame. |
[in] | rf | Reference frame in which the velocity is expressed. |
[out] | v_partial_dq | Partial derivative of the frame spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the frame spatial velociy w.r.t. . |
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 spatial velocity 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 frame spatial velocity w.r.t. . |
[out] | v_partial_dv | Partial derivative of the frame spatial velociy w.r.t. . |
Definition at line 74 of file frames-derivatives.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameVelocityDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const SE3Tpl< context::Scalar, context::Options > & | , | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getFrameVelocityDerivatives< context::Scalar, context::Options, JointCollectionDefaultTpl, context::Matrix6xs, context::Matrix6xs > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex, | ||
const | ReferenceFrame, | ||
const Eigen::MatrixBase< context::Matrix6xs > & | , | ||
const Eigen::MatrixBase< context::Matrix6xs > & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x& pinocchio::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.
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. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix3x& pinocchio::getJacobianComFromCrba< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
void pinocchio::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.
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::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.
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. . |
void pinocchio::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.
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. . |
Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> pinocchio::getJointJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | reference_frame | ||
) |
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame, in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame or in the local frame (rf = LOCAL) of the joint.
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] | joint_id | The index of the joint. |
[in] | reference_frame | Reference frame in which the result is expressed. |
Definition at line 127 of file jacobian.hpp.
void pinocchio::getJointJacobian | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | reference_frame, | ||
const Eigen::MatrixBase< Matrix6Like > & | J | ||
) |
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame options.
For the LOCAL reference frame, the Jacobian from the joint frame to the world frame is such that , where is the velocity of the origin of the moving joint frame relative to the fixed world frame, projected into the basis of the joint frame. LOCAL_WORLD_ALIGNED is the same velocity but projected into the world frame basis.
For the WORLD reference frame, the Jacobian from the joint frame to the world frame is such that , where is the spatial velocity of the joint frame. The linear component of this spatial velocity is the velocity of a (possibly imaginary) point attached to the moving joint frame j which is traveling through the origin of the world frame at that instant. The angular component is the instantaneous angular velocity of the joint frame as viewed in the world frame.
When serialized to a 6D vector, the order of coordinates is: three linear followed by three angular.
For further details regarding the different velocities or the Jacobian see Chapters 2 and 3 respectively in A Mathematical Introduction to Robotic Manipulation by Murray, Li and Sastry.
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] | joint_id | The id of the joint. |
[in] | reference_frame | Reference frame in which the result 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.fill(0.). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Matrix6xs pinocchio::getJointJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame | ||
) |
void pinocchio::getJointJacobianTimeVariation | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const JointIndex | joint_id, | ||
const ReferenceFrame | reference_frame, | ||
const Eigen::MatrixBase< Matrix6Like > & | dJ | ||
) |
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (rf = WORLD), in the local world aligned (rf = LOCAL_WORLD_ALIGNED) frame 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] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | joint_id | The id of the joint. |
[in] | reference_frame | Reference frame in which the result is expressed. |
[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.). |
Tensor<Scalar, 3, Options> pinocchio::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.
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 416 of file kinematics-derivatives.hpp.
void pinocchio::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.
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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI Tensor<context::Scalar, 3, context::Options> pinocchio::getJointKinematicHessian< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame | ||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::getJointKinematicHessian< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame, | ||
Tensor< context::Scalar, 3, context::Options > & | |||
) |
void pinocchio::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.
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. . |
PINOCCHIO_DEPRECATED void pinocchio::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.
[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.
void pinocchio::getPointClassicAccelerationDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Model::JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix3xOut1 > & | v_point_partial_dq, | ||
const Eigen::MatrixBase< Matrix3xOut2 > & | a_point_partial_dq, | ||
const Eigen::MatrixBase< Matrix3xOut3 > & | a_point_partial_dv, | ||
const Eigen::MatrixBase< Matrix3xOut4 > & | a_point_partial_da | ||
) |
Computes the partial derivatives of the classic acceleration of a point given by its placement information w.r.t. the joint frame. 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_point_partial_dq. v_point_partial_dv is not computed it is equal to a_point_partial_da.
JointCollection | Collection of Joint types. |
Matrix3xOut1 | Matrix3x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector. |
Matrix3xOut2 | Matrix3x containing the partial derivatives of the spatial acceleration with respect to the joint configuration vector. |
Matrix3xOut3 | Matrix3x containing the partial derivatives of the spatial acceleration with respect to the joint velocity vector. |
Matrix3xOut4 | Matrix3x 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] | joint_id | Index of the joint in model. |
[in] | placement | Relative placement of the point w.r.t. the joint frame. |
[in] | rf | Reference frame in which the Jacobian is expressed (either LOCAL or LOCAL_WORLD_ALIGNED). |
[out] | v_point_partial_dq | Partial derivative of the point velocity w.r.t. . |
[out] | a_point_partial_dq | Partial derivative of the point classic acceleration w.r.t. . |
[out] | a_point_partial_dv | Partial derivative of the point classic acceleration w.r.t. . |
[out] | a_point_partial_da | Partial derivative of the point classic acceleration w.r.t. . |
void pinocchio::getPointClassicAccelerationDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Model::JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix3xOut1 > & | v_point_partial_dq, | ||
const Eigen::MatrixBase< Matrix3xOut2 > & | v_point_partial_dv, | ||
const Eigen::MatrixBase< Matrix3xOut3 > & | a_point_partial_dq, | ||
const Eigen::MatrixBase< Matrix3xOut4 > & | a_point_partial_dv, | ||
const Eigen::MatrixBase< Matrix3xOut5 > & | a_point_partial_da | ||
) |
Computes the partial derivaties of the classic acceleration of a point given by its placement information w.r.t. to the joint frame. 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_point_partial_dq and v_point_partial_dv..
JointCollection | Collection of Joint types. |
Matrix3xOut1 | Matrix3x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector. |
Matrix3xOut2 | Matrix3x containing the partial derivatives of the spatial velocity with respect to the joint velocity vector. |
Matrix3xOut3 | Matrix3x containing the partial derivatives of the spatial acceleration with respect to the joint configuration vector. |
Matrix3xOut4 | Matrix3x containing the partial derivatives of the spatial acceleration with respect to the joint velocity vector. |
Matrix3xOut5 | Matrix3x 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] | joint_id | Index of the joint in model. |
[in] | placement | Relative placement of the point w.r.t. the joint frame. |
[in] | rf | Reference frame in which the Jacobian is expressed (either LOCAL or LOCAL_WORLD_ALIGNED). |
[out] | v_point_partial_dq | Partial derivative of the point velocity w.r.t. . |
[out] | v_point_partial_dv | Partial derivative of the point velociy w.r.t. . |
[out] | a_point_partial_dq | Partial derivative of the point classic acceleration w.r.t. . |
[out] | a_point_partial_dv | Partial derivative of the point classic acceleration w.r.t. . |
[out] | a_point_partial_da | Partial derivative of the point classic acceleration w.r.t. . |
void pinocchio::getPointVelocityDerivatives | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Model::JointIndex | joint_id, | ||
const SE3Tpl< Scalar, Options > & | placement, | ||
const ReferenceFrame | rf, | ||
const Eigen::MatrixBase< Matrix3xOut1 > & | v_point_partial_dq, | ||
const Eigen::MatrixBase< Matrix3xOut2 > & | v_point_partial_dv | ||
) |
Computes the partial derivatives of the velocity of a point given by its placement information w.r.t. the joint frame. You must first call computForwardKinematicsDerivatives before calling this function.
JointCollection | Collection of Joint types. |
Matrix3xOut1 | Matrix3x containing the partial derivatives of the spatial velocity with respect to the joint configuration vector. |
Matrix3xOut2 | Matrix3x containing the partial derivatives of the spatial velocity 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] | joint_id | Index of the joint in model. |
[in] | placement | Relative placement of the point w.r.t. the joint frame. |
[in] | rf | Reference frame in which the Jacobian is expressed (either LOCAL or LOCAL_WORLD_ALIGNED). |
[out] | v_point_partial_dq | Partial derivative of the point velocity w.r.t. . |
[out] | v_point_partial_dv | Partial derivative of the point velociy w.r.t. . |
struct PINOCCHIO_UNSUPPORTED_MESSAGE ("The API will change towards more flexibility") RigidConstraintModelTpl size_t pinocchio::getTotalConstraintSize | ( | const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > & | contact_models | ) |
Contact model structure containg all the info describing the rigid contact model.
Definition at line 810 of file algorithm/contact-info.hpp.
MotionTpl<Scalar, Options> pinocchio::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.
[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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI MotionTpl<context::Scalar, context::Options> pinocchio::getVelocity< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const | JointIndex, | ||
const | ReferenceFrame | ||
) |
|
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 19 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 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 321 of file spatial/explog.hpp.
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 273 of file 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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::impulseDynamics | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< ConfigVectorType > & | q, | ||
const Eigen::MatrixBase< TangentVectorType1 > & | v_before, | ||
const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > & | contact_models, | ||
std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > & | contact_datas, | ||
const Scalar | r_coeff, | ||
const ProximalSettingsTpl< Scalar > & | settings | ||
) |
Compute the impulse dynamics with contact constraints. Internally, pinocchio::crba is called.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
TangentVectorType1 | Type of the joint velocity vector. |
Allocator | Allocator class for the std::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 (size model.nq). |
[in] | v_before | The joint velocity (size model.nv). |
[in] | contact_models | Vector of contact information related to the problem. |
[in] | contact_datas | Vector of contact datas related to the contact models. |
[in] | r_coeff | coefficient of restitution: must be in [0.,1.] |
[in] | mu | Damping factor for cholesky decomposition. 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. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs& pinocchio::impulseDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, typename context::RigidConstraintModelVector::allocator_type, typename context::RigidConstraintDataVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::RigidConstraintModelVector & | , | ||
context::RigidConstraintDataVector & | , | ||
const context::Scalar | , | ||
const ProximalSettingsTpl< context::Scalar > & | |||
) |
|
inline |
Init the forward dynamics data according to the contact information contained in contact_models.
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. |
Allocator | Allocator class for the std::vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | contact_models | Vector of contact information related to the problem. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::initConstraintDynamics< context::Scalar, context::Options, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type > | ( | const context::Model & | , |
context::Data & | , | ||
const context::RigidConstraintModelVector & | |||
) |
|
inline |
|
inline |
Init the data according to the contact information contained in contact_models.
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. |
Allocator | Allocator class for the std::vector. |
[in] | model | The model structure of the rigid body system. |
[in] | data | The data structure of the rigid body system. |
[in] | contact_models | Vector of contact information related to the problem. |
|
inline |
Visit a LieGroupVariant to call its integrate method.
[in] | lg | the LieGroupVariant. |
[in] | q | the starting configuration. |
[in] | v | the tangent velocity. |
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 70 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 70 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::integrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::integrate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::integrate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::integrate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
void pinocchio::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.
[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 1046 of file joint-configuration.hpp.
void pinocchio::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.
[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 1046 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::integrateCoeffWiseJacobian< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::integrateCoeffWiseJacobian< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::MatrixXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::MatrixXs > & | |||
) |
|
inline |
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 127 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 127 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::interpolate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::interpolate< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::interpolate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::interpolate< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
|
inline |
Definition at line 273 of file math/matrix.hpp.
bool pinocchio::isEqual | ( | const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > & | cdata_generic, |
const ConstraintDataBase< ConstraintDataDerived > & | cdata | ||
) |
Definition at line 273 of file constraint-model-visitor.hpp.
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. |
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. |
|
inline |
Check whether the input vector is Normalized within the given precision.
[in] | vec | Input vector |
[in] | prec | Required precision |
Definition at line 206 of file math/matrix.hpp.
|
inline |
bool pinocchio::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.
[in] | model | Model of the kinematic tree. |
[in] | q | Configuration to check (size model.nq). |
[in] | prec | Precision. |
Definition at line 933 of file joint-configuration.hpp.
bool pinocchio::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.
[in] | model | Model of the kinematic tree. |
[in] | q | Configuration to check (size model.nq). |
[in] | prec | Precision. |
Definition at line 933 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool pinocchio::isNormalized< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool pinocchio::isNormalized< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | |||
) |
|
inline |
bool pinocchio::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.
[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 993 of file joint-configuration.hpp.
bool pinocchio::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.
[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 993 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool pinocchio::isSameConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool pinocchio::isSameConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const context::Scalar & | |||
) |
|
inline |
Check whether the input matrix is Unitary within the given precision.
[in] | mat | Input matrix |
[in] | prec | Required precision |
Definition at line 155 of file math/matrix.hpp.
|
inline |
Definition at line 59 of file math/matrix.hpp.
void pinocchio::jacobian | ( | const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > & | cmodel, |
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > & | cdata, | ||
const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | ||
const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
const Eigen::MatrixBase< JacobianMatrix > & | jacobian_matrix | ||
) |
Definition at line 199 of file constraint-model-visitor.hpp.
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x& pinocchio::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 (.
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. |
const DataTpl<Scalar, Options, JointCollectionTpl>::Matrix3x& pinocchio::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 (.
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. |
void pinocchio::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 (.
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(). |
void pinocchio::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.
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 | ||
) |
Eigen::Matrix<typename MotionDerived::Scalar, 6, 6, MotionDerived::Options> pinocchio::Jexp6 | ( | const MotionDense< MotionDerived > & | nu | ) |
Derivative of exp6 Computed as the inverse of Jlog6.
Definition at line 593 of file 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 496 of file 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 584 of file 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 262 of file 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 240 of file spatial/explog.hpp.
Eigen::Matrix<Scalar, 6, 6, Options> pinocchio::Jlog6 | ( | const SE3Tpl< Scalar, Options > & | M | ) |
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
\cheatsheet For , let and . Then, we have the following partial (right) Jacobians:
\cheatsheet Let , and . Then, we have the following partial (right) Jacobian:
[in] | M | The rigid transformation. |
Definition at line 679 of file 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
\cheatsheet For , let and . Then, we have the following partial (right) Jacobians:
\cheatsheet Let , and . Then, we have the following partial (right) Jacobian:
Definition at line 668 of file spatial/explog.hpp.
|
inline |
Visit a JointDataVariant through JointConstraintVisitor to get the joint constraint as a dense constraint.
[in] | jdata | The joint data to visit. |
|
inline |
Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector.
[in] | jdata | The joint data to visit. |
|
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 |
Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector.
[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] | joint_id | The id of the joint. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::BodyRegressorType& pinocchio::jointBodyRegressor< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
JointIndex | |||
) |
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 103 of file spatial/explog.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 83 of file 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 475 of file spatial/explog.hpp.
MotionTpl<typename Vector3Like::Scalar, Vector3Like::Options> pinocchio::log6 | ( | const Eigen::QuaternionBase< QuaternionLike > & | quat, |
const Eigen::MatrixBase< Vector3Like > & | vec | ||
) |
Log: SE3 -> se3.
Pseudo-inverse of exp from , using the quaternion representation of the rotation.
[in] | quat | The rotation quaternion. |
[in] | vec | The translation vector. |
Definition at line 454 of file 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 435 of file spatial/explog.hpp.
auto pinocchio::make_const_ref | ( | Eigen::MatrixBase< M > const & | m | ) | -> Eigen::Ref<typename M::PlainObject const> |
Definition at line 88 of file context/generic.hpp.
Eigen::Ref<typename Derived::PlainObject> pinocchio::make_ref | ( | const Eigen::MatrixBase< Derived > & | x | ) |
Definition at line 81 of file context/generic.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. |
Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> pinocchio::neutral | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model | ) |
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 1426 of file joint-configuration.hpp.
Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> pinocchio::neutral | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model | ) |
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 1426 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). |
[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 363 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 363 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::neutral< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | ) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::neutral< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::neutral< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | ) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::neutral< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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:
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 |
Normalize the input vector.
[in] | vec | Input vector |
Definition at line 249 of file math/matrix.hpp.
|
inline |
void pinocchio::normalize | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | qout | ||
) |
Normalize a configuration vector.
[in] | model | Model of the kinematic tree. |
[in,out] | q | Configuration to normalize (size model.nq). |
Definition at line 887 of file joint-configuration.hpp.
void pinocchio::normalize | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | qout | ||
) |
Normalize a configuration vector.
[in] | model | Model of the kinematic tree. |
[in,out] | q | Configuration to normalize (size model.nq). |
Definition at line 887 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::normalize< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::normalize< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
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 80 of file rotation.hpp.
|
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 configuration space.
[in] | lg | the LieGroupVariant. |
|
inline |
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space.
[in] | jmodel | The JointModelVariant |
|
inline |
Visit a LieGroupVariant to get the dimension of the Lie group tangent space.
[in] | lg | the LieGroupVariant. |
bool pinocchio::operator!= | ( | const JointDataBase< JointDataDerived > & | joint_data, |
const JointDataTpl< Scalar, Options, JointCollectionTpl > & | joint_data_generic | ||
) |
Definition at line 447 of file joint-generic.hpp.
bool pinocchio::operator!= | ( | const JointModelBase< JointModelDerived > & | joint_model, |
const JointModelTpl< Scalar, Options, JointCollectionTpl > & | joint_model_generic | ||
) |
Definition at line 471 of file joint-generic.hpp.
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl<S, O> > pinocchio::operator* | ( | const Eigen::MatrixBase< LhsMatrixType > & | lhs, |
const TridiagonalSymmetricMatrixTpl< S, O > & | rhs | ||
) |
Definition at line 319 of file math/tridiagonal-matrix.hpp.
|
inline |
Definition at line 441 of file joint-planar.hpp.
|
inline |
Definition at line 358 of file joint-spherical.hpp.
|
inline |
Definition at line 455 of file joint-translation.hpp.
const MatrixMatrixProduct< typename Eigen::internal::remove_const< typename SizeDepType<3>::ColsReturn<Matrix6Like>::ConstType>::type, typename JointMotionSubspaceSphericalZYXTpl<S2, O2>::Matrix3>::type pinocchio::operator* | ( | const Eigen::MatrixBase< Matrix6Like > & | Y, |
const JointMotionSubspaceSphericalZYXTpl< S2, O2 > & | S | ||
) |
Definition at line 250 of file joint-spherical-ZYX.hpp.
MultiplicationOp<Eigen::MatrixBase<MatrixDerived>, ConstraintDerived>::ReturnType pinocchio::operator* | ( | const Eigen::MatrixBase< MatrixDerived > & | Y, |
const JointMotionSubspaceBase< ConstraintDerived > & | constraint | ||
) |
Operation Y_matrix * S used in the ABA algorithm for instance
Definition at line 161 of file joint-motion-subspace-base.hpp.
|
inline |
Definition at line 137 of file joint-free-flyer.hpp.
|
inline |
Definition at line 410 of file joint-planar.hpp.
|
inline |
Definition at line 343 of file joint-spherical.hpp.
Eigen::Matrix<S1, 6, 3, O1> pinocchio::operator* | ( | const InertiaTpl< S1, O1 > & | Y, |
const JointMotionSubspaceSphericalZYXTpl< S2, O2 > & | S | ||
) |
Definition at line 231 of file joint-spherical-ZYX.hpp.
|
inline |
Definition at line 441 of file joint-translation.hpp.
MultiplicationOp<InertiaTpl<Scalar, Options>, ConstraintDerived>::ReturnType pinocchio::operator* | ( | const InertiaTpl< Scalar, Options > & | Y, |
const JointMotionSubspaceBase< ConstraintDerived > & | constraint | ||
) |
Operation Y * S used in the CRBA algorithm for instance
Definition at line 150 of file joint-motion-subspace-base.hpp.
MotionRef<const Vector6Like> pinocchio::operator* | ( | const JointMotionSubspaceIdentityTpl< Scalar, Options > & | , |
const Eigen::MatrixBase< Vector6Like > & | v | ||
) |
Definition at line 124 of file joint-free-flyer.hpp.
JointMotionSubspaceTransposeBase<ConstraintDerived>::StDiagonalMatrixSOperationReturnType pinocchio::operator* | ( | const JointMotionSubspaceTransposeBase< ConstraintDerived > & | , |
const JointMotionSubspaceBase< ConstraintDerived > & | S | ||
) |
Definition at line 193 of file joint-motion-subspace-base.hpp.
Eigen::Matrix<_Scalar, 1, 1, _Options> pinocchio::operator* | ( | const typename JointMotionSubspaceHelicalTpl< _Scalar, _Options, _axis >::TransposeConst & | S_transpose, |
const JointMotionSubspaceHelicalTpl< _Scalar, _Options, _axis > & | S | ||
) |
Definition at line 606 of file joint-helical.hpp.
Eigen::Matrix<_Scalar, 1, 1, _Options> pinocchio::operator* | ( | const typename JointMotionSubspaceHelicalUnalignedTpl< _Scalar, _Options >::TransposeConst & | S_transpose, |
const JointMotionSubspaceHelicalUnalignedTpl< _Scalar, _Options > & | S | ||
) |
Definition at line 445 of file joint-helical-unaligned.hpp.
internal::RHSScalarMultiplication< MotionDerived, typename MotionDerived::Scalar>::ReturnType pinocchio::operator* | ( | const typename MotionDerived::Scalar & | alpha, |
const MotionBase< MotionDerived > & | motion | ||
) |
Definition at line 218 of file motion-base.hpp.
traits<F1>::ForcePlain pinocchio::operator* | ( | const typename traits< F1 >::Scalar | alpha, |
const ForceDense< F1 > & | f | ||
) |
Basic operations specialization.
Definition at line 267 of file force-dense.hpp.
traits<M1>::MotionPlain pinocchio::operator* | ( | const typename traits< M1 >::Scalar | alpha, |
const MotionDense< M1 > & | v | ||
) |
Definition at line 324 of file motion-dense.hpp.
|
inline |
Definition at line 118 of file motion-zero.hpp.
MotionDerived::MotionPlain pinocchio::operator+ | ( | const MotionHelicalTpl< S1, O1, axis > & | m1, |
const MotionDense< MotionDerived > & | m2 | ||
) |
Definition at line 384 of file joint-helical.hpp.
MotionDerived::MotionPlain pinocchio::operator+ | ( | const MotionHelicalUnalignedTpl< S1, O1 > & | m1, |
const MotionDense< MotionDerived > & | m2 | ||
) |
Definition at line 213 of file joint-helical-unaligned.hpp.
|
inline |
Definition at line 222 of file joint-planar.hpp.
MotionDerived::MotionPlain pinocchio::operator+ | ( | const MotionPrismaticTpl< Scalar, Options, axis > & | m1, |
const MotionDense< MotionDerived > & | m2 | ||
) |
Definition at line 183 of file joint-prismatic.hpp.
|
inline |
Definition at line 188 of file joint-prismatic-unaligned.hpp.
MotionDerived::MotionPlain pinocchio::operator+ | ( | const MotionRevoluteTpl< S1, O1, axis > & | m1, |
const MotionDense< MotionDerived > & | m2 | ||
) |
Definition at line 361 of file joint-revolute.hpp.
|
inline |
Definition at line 199 of file joint-revolute-unaligned.hpp.
|
inline |
Definition at line 196 of file joint-spherical.hpp.
|
inline |
Definition at line 190 of file joint-translation.hpp.
|
inline |
Definition at line 124 of file motion-zero.hpp.
|
inline |
Definition at line 253 of file multibody/frame.hpp.
|
inline |
Definition at line 153 of file joint-composite.hpp.
|
inline |
Definition at line 579 of file joint-composite.hpp.
std::ostream & pinocchio::operator<< | ( | std::ostream & | os, |
const LieGroupBase< Derived > & | lg | ||
) |
Definition at line 23 of file cartesian-product-liegroups.cpp.
std::ostream & pinocchio::operator<< | ( | std::ostream & | os, |
const LieGroupGenericTpl< LieGroupCollection > & | lg | ||
) |
Definition at line 28 of file cartesian-product-liegroups.cpp.
bool pinocchio::operator== | ( | const ConstraintDataBase< ConstraintDataDerived > & | data1, |
const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > & | data2 | ||
) |
Definition at line 104 of file constraint-data-generic.hpp.
bool pinocchio::operator== | ( | const JointDataBase< JointDataDerived > & | joint_data, |
const JointDataTpl< Scalar, Options, JointCollectionTpl > & | joint_data_generic | ||
) |
Definition at line 435 of file joint-generic.hpp.
bool pinocchio::operator== | ( | const JointModelBase< JointModelDerived > & | joint_model, |
const JointModelTpl< Scalar, Options, JointCollectionTpl > & | joint_model_generic | ||
) |
Definition at line 459 of file joint-generic.hpp.
traits<F1>::ForcePlain pinocchio::operator^ | ( | const MotionDense< M1 > & | v, |
const ForceBase< F1 > & | f | ||
) |
Definition at line 317 of file motion-dense.hpp.
traits<M1>::MotionPlain pinocchio::operator^ | ( | const MotionDense< M1 > & | v1, |
const MotionDense< M2 > & | v2 | ||
) |
Basic operations specialization.
Definition at line 311 of file motion-dense.hpp.
EIGEN_STRONG_INLINE MotionDerived::MotionPlain pinocchio::operator^ | ( | const MotionDense< MotionDerived > & | m1, |
const MotionHelicalTpl< S2, O2, axis > & | m2 | ||
) |
Definition at line 393 of file joint-helical.hpp.
EIGEN_STRONG_INLINE MotionDerived::MotionPlain pinocchio::operator^ | ( | const MotionDense< MotionDerived > & | m1, |
const MotionHelicalUnalignedTpl< S2, O2 > & | m2 | ||
) |
Definition at line 222 of file joint-helical-unaligned.hpp.
|
inline |
Definition at line 402 of file joint-planar.hpp.
EIGEN_STRONG_INLINE MotionDerived::MotionPlain pinocchio::operator^ | ( | const MotionDense< MotionDerived > & | m1, |
const MotionPrismaticTpl< S2, O2, axis > & | m2 | ||
) |
Definition at line 193 of file joint-prismatic.hpp.
|
inline |
Definition at line 197 of file joint-prismatic-unaligned.hpp.
EIGEN_STRONG_INLINE MotionDerived::MotionPlain pinocchio::operator^ | ( | const MotionDense< MotionDerived > & | m1, |
const MotionRevoluteTpl< S2, O2, axis > & | m2 | ||
) |
Definition at line 370 of file joint-revolute.hpp.
|
inline |
Definition at line 208 of file joint-revolute-unaligned.hpp.
|
inline |
Definition at line 335 of file joint-spherical.hpp.
|
inline |
Definition at line 433 of file joint-translation.hpp.
void pinocchio::orthonormalisation | ( | const Eigen::MatrixBase< MatrixType > & | basis, |
const Eigen::MatrixBase< VectorType > & | vec_ | ||
) |
Perform the Gram-Schmidt orthonormalisation on the input/output vector for a given input basis.
[in] | basis | Orthonormal basis |
[in,out] | vec | Vector to orthonomarlize wrt the input basis |
Definition at line 20 of file gram-schmidt-orthonormalisation.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 27 of file math/fwd.hpp.
typedef pinocchio::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointData | ) |
typedef pinocchio::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointModel | ) |
pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER | ( | ABA | ) |
pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER | ( | CRBA | ) |
pinocchio::PINOCCHIO_DEFINE_ALGO_CHECKER | ( | Parent | ) |
Simple model checker, that assert that model.parents is indeed a tree.
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | equal_to_op | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | greater_than_op | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | greater_than_or_equal_to_op | , |
>= | |||
) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | less_than_op | ) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | less_than_or_equal_to_op | , |
<= | |||
) |
pinocchio::PINOCCHIO_DEFINE_COMPARISON_OP | ( | not_equal_to_op | , |
! | |||
) |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | ConfigVectorIn1 | ) | const |
Interpolate two configurations for a given model.
Squared distance between two configurations.
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 | 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 | ( | ConfigVectorIn1 | ) | const |
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) |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | ConfigVectorType | ) | const |
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) |
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | ConfigVectorType | ) | const |
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) |
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 104 of file rotation.hpp.
|
inline |
|
inline |
Computes the classic acceleration from a given spatial velocity and spatial acceleration.
Motion1 | type of the input spatial velocity. |
Motion2 | type of the input spatial acceleration. |
[in] | spatial_velocity | input spatial velocity. |
[in] | spatial_acceleration | input spatial acceleration. |
|
inline |
Computes the classic acceleration of a given frame B knowing the spatial velocity and spatial acceleration of a frame A and the relative placement between these two frames.
Motion1 | type of the input spatial velocity. |
Motion2 | type of the input spatial acceleration. |
SE3Scalar | Scalar type of the SE3 object. |
SE3Options | Options of the SE3 object. |
[in] | spatial_velocity | input spatial velocity. |
[in] | spatial_acceleration | input spatial acceleration. |
[in] | placement | relative placement betwen the frame A and the frame B. |
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 144 of file joint-free-flyer.hpp.
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelFreeFlyerTpl | ) |
Free-flyer joint in .
A free-flyer joint adds seven coordinates to the configuration space. Given a configuration vector q
:
q[idx_q:idx_q + 3]
are the translation coordinates, in meters, representing the position of the child frame in the parent frame.q[idx_q + 3:idx_q + 7]
is a unit quaternion representing the rotation from the child frame to the parent frame, with quaternion coordinates ordered as (x, y, z, w).Likewise, a free-flyer joint adds six coordinates to the tangent space. Let's consider a tangent vector v
, say, a velocity vector. Following Featherstone's convention, all our tangent vectors are body rather than spatial vectors:
v[idx_v:idx_v + 3]
is the linear velocity, in meters / second, corresponding to the linear velocity of the child frame with respect to the parent frame, expressed in the child frame (body linear velocity of the child frame).v[idx_v + 3:idx_v + 6]
is the angular velocity, in radians / second, corresponding to the angular velocity from the child frame to the parent frame, expressed in the child frame (body angular velocity of the child frame). pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelHelicalUnalignedTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelPlanarTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelPrismaticUnalignedTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelRevoluteUnalignedTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelRevoluteUnboundedUnalignedTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelSphericalTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelSphericalZYXTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelTranslationTpl | ) |
pinocchio::PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION | ( | JointModelUniversalTpl | ) |
struct pinocchio::PINOCCHIO_UNSUPPORTED_MESSAGE | ( | "The API will change towards more flexibility" | ) |
Contact Cholesky decomposition structure. This structure allows to compute in a efficient and parsimonious way the Cholesky decomposition of the KKT matrix related to the contact dynamics. Such a decomposition is usefull when computing both the forward dynamics in contact or the related analytical derivatives.
_Scalar | Scalar type. |
_Options | Alignment Options of the Eigen objects contained in the data structure. |
Data information related to the Sparsity structure of the Cholesky decompostion
Definition at line 55 of file algorithm/contact-cholesky.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 utils/version.hpp.
|
inline |
The Popov-Vereshchagin algorithm. It computes constrained forward dynamics, aka the joint accelerations and constraint forces given the current state, actuation and the constraints on the system. All the quantities are expressed in the LOCAL coordinate systems of the joint frames.
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. |
Allocator | Allocator class for the std::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] | contact_models | Vector of contact models. |
[in] | contact_datas | Vector of contact data. |
[in] | settings | Proximal settings (mu, accuracy and maximal number of iterations). |
|
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 315 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 315 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::randomConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | ) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::randomConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::randomConfiguration< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::randomConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | ) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::randomConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::randomConfiguration< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
|
inline |
Generate a random string composed of alphanumeric symbols of a given length.
[in] | len | The length of the output string. |
Definition at line 21 of file string-generator.hpp.
void pinocchio::reachableWorkspace | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q0, | ||
const double | time_horizon, | ||
const int | frame_id, | ||
Eigen::MatrixXd & | vertex, | ||
const ReachableSetParams & | params = ReachableSetParams() |
||
) |
Computes the reachable workspace on a fixed time horizon. For more information, please see https://gitlab.inria.fr/auctus-team/people/antunskuric/pycapacity.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | q | The initial joint configuration vector (dim model.nq). |
[in] | frame_id | Index of the frame for which the workspace should be computed. |
[in] | time_horizon | time horizon for which the polytope will be computed (in seconds) |
[in] | params | parameters of the algorithm |
[out] | points | inside of the reachable workspace |
void pinocchio::reachableWorkspaceHull | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorType > & | q0, | ||
const double | time_horizon, | ||
const int | frame_id, | ||
ReachableSetResults & | res, | ||
const ReachableSetParams & | params = ReachableSetParams() |
||
) |
Computes the convex Hull reachable workspace on a fixed time horizon. For more information, please see https://gitlab.inria.fr/auctus-team/people/antunskuric/pycapacity.
JointCollection | Collection of Joint types. |
ConfigVectorType | Type of the joint configuration vector. |
[in] | model | The model structure of the rigid body system. |
[in] | q | The initial joint configuration vector (dim model.nq). |
[in] | frame_id | Index of the frame for which the workspace should be computed. |
[in] | time_horizon | time horizon for which the polytope will be computed (in seconds) |
[in] | params | parameters of the algorithm |
[out] | res | Results of algorithm |
|
inline |
Replace string from with to in input_str.
[in] | input_str | string on which replace operates. |
[in] | from | The string to replace. |
[in] | to | The string to replace the old value with. |
Definition at line 22 of file string.hpp.
VectorLike::Scalar pinocchio::retrieveLargestEigenvalue | ( | const Eigen::MatrixBase< VectorLike > & | eigenvector | ) |
Compute the lagest eigenvalue of a given matrix. This is taking the eigenvector computed by the function computeLargestEigenvector.
Definition at line 206 of file eigenvalues.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:// |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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.
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). |
const DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType& pinocchio::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.
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) |
void pinocchio::rneaInParallel | ( | const size_t | 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 39 of file parallel/rnea.hpp.
std::vector< std::string > pinocchio::rosPaths | ( | ) |
Parse the environment variables ROS_PACKAGE_PATH / AMENT_PREFIX_PATH and extract paths.
Definition at line 60 of file file-explorer.cpp.
To pinocchio::scalar_cast | ( | const From & | value | ) |
|
inline |
|
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 27 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 249 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 249 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::squaredDistance< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::squaredDistance< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs pinocchio::squaredDistance< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::squaredDistance< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
Scalar pinocchio::squaredDistanceSum | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const Eigen::MatrixBase< ConfigVectorIn1 > & | q0, | ||
const Eigen::MatrixBase< ConfigVectorIn2 > & | q1 | ||
) |
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 795 of file joint-configuration.hpp.
Scalar pinocchio::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 .
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 795 of file joint-configuration.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::squaredDistanceSum< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::Scalar pinocchio::squaredDistanceSum< LieGroupMap, context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs, context::VectorXs > | ( | const context::Model & | , |
const Eigen::MatrixBase< context::VectorXs > & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
|
inline |
Visit a JointDataTpl through JointStUInertiaVisitor to get St*I*S matrix of the inertia matrix decomposition.
[in] | jdata | The joint data to visit. |
void pinocchio::toCSVfile | ( | const std::string & | filename, |
const Eigen::MatrixBase< Derived > & | matrix | ||
) |
|
inline |
Definition at line 14 of file collision/fcl-pinocchio-conversions.hpp.
|
inline |
Definition at line 20 of file collision/fcl-pinocchio-conversions.hpp.
void pinocchio::toRotationMatrix | ( | const Eigen::MatrixBase< Vector3 > & | axis, |
const Scalar & | angle, | ||
const Eigen::MatrixBase< Matrix3 > & | res | ||
) |
Computes a rotation matrix from a vector and the angular value orientations values.
Definition at line 64 of file rotation.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 26 of file rotation.hpp.
|
inline |
Evaluate the product of a triangular matrix times a matrix. Eigen showing a bug at this level, in the case of vector entry.
[in] | lhs_mat | Input tringular matrix |
[in] | rhs_mat | Right hand side operand in the multplication |
[in] | res | Resulting matrix |
Definition at line 59 of file math/triangular-matrix.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 matrix. |
|
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 |
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. |
template const PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI SE3Tpl<context::Scalar, context::Options>& pinocchio::updateFramePlacement< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | , | ||
const | FrameIndex | ||
) |
|
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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::updateFramePlacements< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
|
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 |
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). |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::updateGeometryPlacements< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
const context::Data & | , | ||
const GeometryModel & | , | ||
GeometryData & | |||
) |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::updateGeometryPlacements< context::Scalar, context::Options, JointCollectionDefaultTpl, context::VectorXs > | ( | const context::Model & | , |
context::Data & | , | ||
const GeometryModel & | , | ||
GeometryData & | , | ||
const Eigen::MatrixBase< context::VectorXs > & | |||
) |
void pinocchio::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.
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. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::updateGlobalPlacements< context::Scalar, context::Options, JointCollectionDefaultTpl > | ( | const context::Model & | , |
context::Data & | |||
) |
const int pinocchio::Dynamic = -1 |
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & pinocchio::lowerLimits |
Definition at line 1306 of file joint-configuration.hpp.
JointCollectionTpl & pinocchio::model |
Definition at line 1082 of file joint-configuration.hpp.
pinocchio::Options |
Definition at line 1082 of file joint-configuration.hpp.
const MotionDense<Motion2> const SE3Tpl<SE3Scalar, SE3Options>& pinocchio::placement |
Definition at line 122 of file spatial/classic-acceleration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & pinocchio::q |
Definition at line 1083 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & pinocchio::q0 |
Definition at line 1137 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & pinocchio::q1 |
Definition at line 1138 of file joint-configuration.hpp.
return pinocchio::res |
Definition at line 57 of file spatial/classic-acceleration.hpp.
const MotionDense< Motion2 > & pinocchio::spatial_acceleration |
Definition at line 55 of file spatial/classic-acceleration.hpp.
pinocchio.submodules = inspect.getmembers(pinocchio_pywrap_default, inspect.ismodule) |
Definition at line 43 of file bindings/python/pinocchio/__init__.py.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > const Scalar & pinocchio::u |
Definition at line 1139 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & pinocchio::upperLimits |
Definition at line 1307 of file joint-configuration.hpp.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & pinocchio::v |
bool pinocchio.WITH_HPP_FCL_BINDINGS = True |
Definition at line 65 of file bindings/python/pinocchio/__init__.py.