|
tsid
1.8.0
Efficient Task Space Inverse Dynamics for Multi-body Systems based on Pinocchio
|
Wrapper for a robot based on pinocchio. More...
#include <tsid/robots/robot-wrapper.hpp>

Public Types | |
| enum | e_RootJointType { FIXED_BASE_SYSTEM = 0 , FLOATING_BASE_SYSTEM = 1 } |
| typedef pinocchio::Model | Model |
| typedef pinocchio::Data | Data |
| typedef pinocchio::Motion | Motion |
| typedef pinocchio::Frame | Frame |
| typedef pinocchio::SE3 | SE3 |
| typedef math::Vector | Vector |
| typedef math::Vector3 | Vector3 |
| typedef math::Vector6 | Vector6 |
| typedef math::Matrix | Matrix |
| typedef math::Matrix3x | Matrix3x |
| typedef math::RefVector | RefVector |
| typedef math::ConstRefVector | ConstRefVector |
| typedef enum tsid::robots::RobotWrapper::e_RootJointType | RootJointType |
Public Member Functions | |
| RobotWrapper (const std::string &filename, const std::vector< std::string > &package_dirs, bool verbose=false) | |
| RobotWrapper (const std::string &filename, const std::vector< std::string > &package_dirs, const pinocchio::JointModelVariant &rootJoint, bool verbose=false) | |
| TSID_DEPRECATED | RobotWrapper (const Model &m, bool verbose=false) |
| RobotWrapper (const Model &m, RootJointType rootJoint, bool verbose=false) | |
| virtual | ~RobotWrapper ()=default |
| virtual int | nq () const |
| virtual int | nq_actuated () const |
| virtual int | nv () const |
| virtual int | na () const |
| virtual bool | is_fixed_base () const |
| const Model & | model () const |
| Accessor to model. More... | |
| Model & | model () |
| void | computeAllTerms (Data &data, const Vector &q, const Vector &v) const |
| const Vector & | rotor_inertias () const |
| const Vector & | gear_ratios () const |
| bool | rotor_inertias (ConstRefVector rotor_inertias) |
| bool | gear_ratios (ConstRefVector gear_ratios) |
| void | com (const Data &data, RefVector com_pos, RefVector com_vel, RefVector com_acc) const |
| const Vector3 & | com (const Data &data) const |
| const Vector3 & | com_vel (const Data &data) const |
| const Vector3 & | com_acc (const Data &data) const |
| const Matrix3x & | Jcom (const Data &data) const |
| const Matrix & | mass (const Data &data) |
| const Vector & | nonLinearEffects (const Data &data) const |
| const SE3 & | position (const Data &data, const Model::JointIndex index) const |
| const Motion & | velocity (const Data &data, const Model::JointIndex index) const |
| const Motion & | acceleration (const Data &data, const Model::JointIndex index) const |
| void | jacobianWorld (const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const |
| void | jacobianLocal (const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const |
| SE3 | framePosition (const Data &data, const Model::FrameIndex index) const |
| void | framePosition (const Data &data, const Model::FrameIndex index, SE3 &framePosition) const |
| Motion | frameVelocity (const Data &data, const Model::FrameIndex index) const |
| Motion | frameVelocityWorldOriented (const Data &data, const Model::FrameIndex index) const |
| void | frameVelocity (const Data &data, const Model::FrameIndex index, Motion &frameVelocity) const |
| Motion | frameAcceleration (const Data &data, const Model::FrameIndex index) const |
| Motion | frameAccelerationWorldOriented (const Data &data, const Model::FrameIndex index) const |
| void | frameAcceleration (const Data &data, const Model::FrameIndex index, Motion &frameAcceleration) const |
| Motion | frameClassicAcceleration (const Data &data, const Model::FrameIndex index) const |
| Motion | frameClassicAccelerationWorldOriented (const Data &data, const Model::FrameIndex index) const |
| void | frameClassicAcceleration (const Data &data, const Model::FrameIndex index, Motion &frameAcceleration) const |
| void | frameJacobianWorld (Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const |
| void | frameJacobianLocal (Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const |
| const Data::Matrix6x & | momentumJacobian (const Data &data) const |
| Vector3 | angularMomentumTimeVariation (const Data &data) const |
| void | setGravity (const Motion &gravity) |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar | Scalar |
Protected Member Functions | |
| void | init () |
| void | updateMd () |
Protected Attributes | |
| Model | m_model |
| Robot model. More... | |
| std::string | m_model_filename |
| bool | m_verbose |
| int | m_nq_actuated |
| int | m_na |
| bool | m_is_fixed_base |
| Vector | m_rotor_inertias |
| Vector | m_gear_ratios |
| Vector | m_Md |
| Matrix | m_M |
| diagonal part of inertia matrix due to rotor inertias More... | |
Wrapper for a robot based on pinocchio.
| typedef pinocchio::Data tsid::robots::RobotWrapper::Data |
| typedef pinocchio::Frame tsid::robots::RobotWrapper::Frame |
| typedef pinocchio::Model tsid::robots::RobotWrapper::Model |
| typedef pinocchio::Motion tsid::robots::RobotWrapper::Motion |
| typedef pinocchio::SE3 tsid::robots::RobotWrapper::SE3 |
| tsid::robots::RobotWrapper::RobotWrapper | ( | const std::string & | filename, |
| const std::vector< std::string > & | package_dirs, | ||
| bool | verbose = false |
||
| ) |
| tsid::robots::RobotWrapper::RobotWrapper | ( | const std::string & | filename, |
| const std::vector< std::string > & | package_dirs, | ||
| const pinocchio::JointModelVariant & | rootJoint, | ||
| bool | verbose = false |
||
| ) |
| tsid::robots::RobotWrapper::RobotWrapper | ( | const Model & | m, |
| bool | verbose = false |
||
| ) |
| tsid::robots::RobotWrapper::RobotWrapper | ( | const Model & | m, |
| RootJointType | rootJoint, | ||
| bool | verbose = false |
||
| ) |
|
virtualdefault |
| const Motion & tsid::robots::RobotWrapper::acceleration | ( | const Data & | data, |
| const Model::JointIndex | index | ||
| ) | const |
| void tsid::robots::RobotWrapper::com | ( | const Data & | data, |
| RefVector | com_pos, | ||
| RefVector | com_vel, | ||
| RefVector | com_acc | ||
| ) | const |
| void tsid::robots::RobotWrapper::computeAllTerms | ( | Data & | data, |
| const Vector & | q, | ||
| const Vector & | v | ||
| ) | const |
| Motion tsid::robots::RobotWrapper::frameAcceleration | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| void tsid::robots::RobotWrapper::frameAcceleration | ( | const Data & | data, |
| const Model::FrameIndex | index, | ||
| Motion & | frameAcceleration | ||
| ) | const |
| Motion tsid::robots::RobotWrapper::frameAccelerationWorldOriented | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| Motion tsid::robots::RobotWrapper::frameClassicAcceleration | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| void tsid::robots::RobotWrapper::frameClassicAcceleration | ( | const Data & | data, |
| const Model::FrameIndex | index, | ||
| Motion & | frameAcceleration | ||
| ) | const |
| Motion tsid::robots::RobotWrapper::frameClassicAccelerationWorldOriented | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| void tsid::robots::RobotWrapper::frameJacobianLocal | ( | Data & | data, |
| const Model::FrameIndex | index, | ||
| Data::Matrix6x & | J | ||
| ) | const |
| void tsid::robots::RobotWrapper::frameJacobianWorld | ( | Data & | data, |
| const Model::FrameIndex | index, | ||
| Data::Matrix6x & | J | ||
| ) | const |
| SE3 tsid::robots::RobotWrapper::framePosition | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| void tsid::robots::RobotWrapper::framePosition | ( | const Data & | data, |
| const Model::FrameIndex | index, | ||
| SE3 & | framePosition | ||
| ) | const |
| Motion tsid::robots::RobotWrapper::frameVelocity | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| void tsid::robots::RobotWrapper::frameVelocity | ( | const Data & | data, |
| const Model::FrameIndex | index, | ||
| Motion & | frameVelocity | ||
| ) | const |
| Motion tsid::robots::RobotWrapper::frameVelocityWorldOriented | ( | const Data & | data, |
| const Model::FrameIndex | index | ||
| ) | const |
| const Vector & tsid::robots::RobotWrapper::gear_ratios | ( | ) | const |
| bool tsid::robots::RobotWrapper::gear_ratios | ( | ConstRefVector | gear_ratios | ) |
|
protected |
|
virtual |
| void tsid::robots::RobotWrapper::jacobianLocal | ( | const Data & | data, |
| const Model::JointIndex | index, | ||
| Data::Matrix6x & | J | ||
| ) | const |
| void tsid::robots::RobotWrapper::jacobianWorld | ( | const Data & | data, |
| const Model::JointIndex | index, | ||
| Data::Matrix6x & | J | ||
| ) | const |
| Model & tsid::robots::RobotWrapper::model | ( | ) |
| const Model & tsid::robots::RobotWrapper::model | ( | ) | const |
Accessor to model.
| const Data::Matrix6x & tsid::robots::RobotWrapper::momentumJacobian | ( | const Data & | data | ) | const |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
| const SE3 & tsid::robots::RobotWrapper::position | ( | const Data & | data, |
| const Model::JointIndex | index | ||
| ) | const |
| const Vector & tsid::robots::RobotWrapper::rotor_inertias | ( | ) | const |
| bool tsid::robots::RobotWrapper::rotor_inertias | ( | ConstRefVector | rotor_inertias | ) |
| void tsid::robots::RobotWrapper::setGravity | ( | const Motion & | gravity | ) |
|
protected |
| const Motion & tsid::robots::RobotWrapper::velocity | ( | const Data & | data, |
| const Model::JointIndex | index | ||
| ) | const |
|
protected |
|
protected |
number of actuators (nv for fixed-based, nv-6 for floating-base robots)
|
protected |
diagonal part of inertia matrix due to rotor inertias
|
protected |
|
protected |
Robot model.
|
protected |
|
protected |
dimension of the configuration space of the actuated DoF (nq for fixed-based, nq-7 for floating-base robots)
|
protected |
|
protected |
|
protected |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar tsid::robots::RobotWrapper::Scalar |