|
template<typename MotionVelocity , typename MotionAcceleration > |
Eigen::Matrix< typename MotionVelocity::Scalar, 6, 10, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionVelocity::Vector3)::Options > | pinocchio::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 | pinocchio::bodyRegressor (const MotionDense< MotionVelocity > &v, const MotionDense< MotionAcceleration > &a, const Eigen::MatrixBase< OutputType > ®ressor) |
| Computes the regressor for the dynamic parameters of a single rigid body. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> |
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. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xReturnType > |
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) |
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> |
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. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xReturnType > |
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) |
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> |
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. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Matrix6xReturnType > |
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) |
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType1 , typename TangentVectorType2 > |
DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | pinocchio::computeJointTorqueRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a) |
| Computes the joint torque regressor that links the joint torque to the dynamic parameters of each link according to the current the robot motion. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > |
const DataTpl< Scalar, Options, JointCollectionTpl >::RowVectorXs & | pinocchio::computePotentialEnergyRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > |
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & | pinocchio::computeStaticRegressor (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q) |
| Computes the static regressor that links the center of mass positions of all the links to the center of mass of the complete model according to the current configuration of the robot. More...
|
|
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> |
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & | pinocchio::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<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> |
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & | pinocchio::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...
|
|