Wrapper for a robot based on pinocchio. More...
#include <robot-wrapper.hpp>
Public Types | |
typedef math::ConstRefVector | ConstRefVector |
typedef pinocchio::Data | Data |
enum | e_RootJointType { FIXED_BASE_SYSTEM = 0, FLOATING_BASE_SYSTEM = 1 } |
typedef pinocchio::Frame | Frame |
typedef math::Matrix | Matrix |
typedef math::Matrix3x | Matrix3x |
typedef pinocchio::Model | Model |
typedef pinocchio::Motion | Motion |
typedef math::RefVector | RefVector |
typedef enum tsid::robots::RobotWrapper::e_RootJointType | RootJointType |
typedef pinocchio::SE3 | SE3 |
typedef math::Vector | Vector |
typedef math::Vector3 | Vector3 |
typedef math::Vector6 | Vector6 |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar | Scalar |
Protected Member Functions | |
void | init () |
void | updateMd () |
Protected Attributes | |
Vector | m_gear_ratios |
bool | m_is_fixed_base |
Matrix | m_M |
diagonal part of inertia matrix due to rotor inertias More... | |
Vector | m_Md |
Model | m_model |
Robot model. More... | |
std::string | m_model_filename |
int | m_na |
int | m_nq_actuated |
Vector | m_rotor_inertias |
bool | m_verbose |
Wrapper for a robot based on pinocchio.
Definition at line 37 of file robots/robot-wrapper.hpp.
typedef math::ConstRefVector tsid::robots::RobotWrapper::ConstRefVector |
Definition at line 53 of file robots/robot-wrapper.hpp.
Definition at line 43 of file robots/robot-wrapper.hpp.
Definition at line 45 of file robots/robot-wrapper.hpp.
Definition at line 50 of file robots/robot-wrapper.hpp.
Definition at line 51 of file robots/robot-wrapper.hpp.
Definition at line 42 of file robots/robot-wrapper.hpp.
Definition at line 44 of file robots/robot-wrapper.hpp.
Definition at line 52 of file robots/robot-wrapper.hpp.
Definition at line 46 of file robots/robot-wrapper.hpp.
Definition at line 47 of file robots/robot-wrapper.hpp.
Definition at line 48 of file robots/robot-wrapper.hpp.
Definition at line 49 of file robots/robot-wrapper.hpp.
Enumerator | |
---|---|
FIXED_BASE_SYSTEM | |
FLOATING_BASE_SYSTEM |
Definition at line 56 of file robots/robot-wrapper.hpp.
tsid::robots::RobotWrapper::RobotWrapper | ( | const std::string & | filename, |
const std::vector< std::string > & | package_dirs, | ||
bool | verbose = false |
||
) |
Definition at line 34 of file src/robots/robot-wrapper.cpp.
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 |
||
) |
Definition at line 58 of file src/robots/robot-wrapper.cpp.
tsid::robots::RobotWrapper::RobotWrapper | ( | const Model & | m, |
RootJointType | rootJoint, | ||
bool | verbose = false |
||
) |
Definition at line 68 of file src/robots/robot-wrapper.cpp.
|
virtualdefault |
const Motion & tsid::robots::RobotWrapper::acceleration | ( | const Data & | data, |
const Model::JointIndex | index | ||
) | const |
Definition at line 190 of file src/robots/robot-wrapper.cpp.
Definition at line 350 of file src/robots/robot-wrapper.cpp.
Definition at line 152 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::com | ( | const Data & | data, |
RefVector | com_pos, | ||
RefVector | com_vel, | ||
RefVector | com_acc | ||
) | const |
Definition at line 145 of file src/robots/robot-wrapper.cpp.
Definition at line 158 of file src/robots/robot-wrapper.cpp.
Definition at line 154 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::computeAllTerms | ( | Data & | data, |
const Vector & | q, | ||
const Vector & | v | ||
) | const |
Definition at line 105 of file src/robots/robot-wrapper.cpp.
Motion tsid::robots::RobotWrapper::frameAcceleration | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 265 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::frameAcceleration | ( | const Data & | data, |
const Model::FrameIndex | index, | ||
Motion & | frameAcceleration | ||
) | const |
Definition at line 274 of file src/robots/robot-wrapper.cpp.
Motion tsid::robots::RobotWrapper::frameAccelerationWorldOriented | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 284 of file src/robots/robot-wrapper.cpp.
Motion tsid::robots::RobotWrapper::frameClassicAcceleration | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 295 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::frameClassicAcceleration | ( | const Data & | data, |
const Model::FrameIndex | index, | ||
Motion & | frameAcceleration | ||
) | const |
Definition at line 307 of file src/robots/robot-wrapper.cpp.
Motion tsid::robots::RobotWrapper::frameClassicAccelerationWorldOriented | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 319 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::frameJacobianLocal | ( | Data & | data, |
const Model::FrameIndex | index, | ||
Data::Matrix6x & | J | ||
) | const |
Definition at line 338 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::frameJacobianWorld | ( | Data & | data, |
const Model::FrameIndex | index, | ||
Data::Matrix6x & | J | ||
) | const |
Definition at line 330 of file src/robots/robot-wrapper.cpp.
SE3 tsid::robots::RobotWrapper::framePosition | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 216 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::framePosition | ( | const Data & | data, |
const Model::FrameIndex | index, | ||
SE3 & | framePosition | ||
) | const |
Definition at line 225 of file src/robots/robot-wrapper.cpp.
Motion tsid::robots::RobotWrapper::frameVelocity | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 235 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::frameVelocity | ( | const Data & | data, |
const Model::FrameIndex | index, | ||
Motion & | frameVelocity | ||
) | const |
Definition at line 244 of file src/robots/robot-wrapper.cpp.
Motion tsid::robots::RobotWrapper::frameVelocityWorldOriented | ( | const Data & | data, |
const Model::FrameIndex | index | ||
) | const |
Definition at line 254 of file src/robots/robot-wrapper.cpp.
const Vector & tsid::robots::RobotWrapper::gear_ratios | ( | ) | const |
Definition at line 120 of file src/robots/robot-wrapper.cpp.
bool tsid::robots::RobotWrapper::gear_ratios | ( | ConstRefVector | gear_ratios | ) |
Definition at line 131 of file src/robots/robot-wrapper.cpp.
|
protected |
Definition at line 89 of file src/robots/robot-wrapper.cpp.
|
virtual |
Definition at line 100 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::jacobianLocal | ( | const Data & | data, |
const Model::JointIndex | index, | ||
Data::Matrix6x & | J | ||
) | const |
Definition at line 207 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::jacobianWorld | ( | const Data & | data, |
const Model::JointIndex | index, | ||
Data::Matrix6x & | J | ||
) | const |
Definition at line 198 of file src/robots/robot-wrapper.cpp.
Definition at line 162 of file src/robots/robot-wrapper.cpp.
Definition at line 164 of file src/robots/robot-wrapper.cpp.
Model& tsid::robots::RobotWrapper::model | ( | ) |
Model & tsid::robots::RobotWrapper::model | ( | ) | const |
Accessor to model.
Definition at line 102 of file src/robots/robot-wrapper.cpp.
const Data::Matrix6x & tsid::robots::RobotWrapper::momentumJacobian | ( | const Data & | data | ) | const |
Definition at line 346 of file src/robots/robot-wrapper.cpp.
|
virtual |
Definition at line 98 of file src/robots/robot-wrapper.cpp.
Definition at line 170 of file src/robots/robot-wrapper.cpp.
|
virtual |
Definition at line 96 of file src/robots/robot-wrapper.cpp.
|
virtual |
Definition at line 99 of file src/robots/robot-wrapper.cpp.
|
virtual |
Definition at line 97 of file src/robots/robot-wrapper.cpp.
const SE3 & tsid::robots::RobotWrapper::position | ( | const Data & | data, |
const Model::JointIndex | index | ||
) | const |
Definition at line 174 of file src/robots/robot-wrapper.cpp.
const Vector & tsid::robots::RobotWrapper::rotor_inertias | ( | ) | const |
Definition at line 119 of file src/robots/robot-wrapper.cpp.
bool tsid::robots::RobotWrapper::rotor_inertias | ( | ConstRefVector | rotor_inertias | ) |
Definition at line 122 of file src/robots/robot-wrapper.cpp.
void tsid::robots::RobotWrapper::setGravity | ( | const Motion & | gravity | ) |
Definition at line 356 of file src/robots/robot-wrapper.cpp.
|
protected |
Definition at line 140 of file src/robots/robot-wrapper.cpp.
const Motion & tsid::robots::RobotWrapper::velocity | ( | const Data & | data, |
const Model::JointIndex | index | ||
) | const |
Definition at line 182 of file src/robots/robot-wrapper.cpp.
|
protected |
Definition at line 185 of file robots/robot-wrapper.hpp.
|
protected |
number of actuators (nv for fixed-based, nv-6 for floating-base robots)
Definition at line 183 of file robots/robot-wrapper.hpp.
|
protected |
diagonal part of inertia matrix due to rotor inertias
Definition at line 187 of file robots/robot-wrapper.hpp.
|
protected |
Definition at line 186 of file robots/robot-wrapper.hpp.
|
protected |
Robot model.
Definition at line 174 of file robots/robot-wrapper.hpp.
|
protected |
Definition at line 175 of file robots/robot-wrapper.hpp.
|
protected |
dimension of the configuration space of the actuated DoF (nq for fixed-based, nq-7 for floating-base robots)
Definition at line 181 of file robots/robot-wrapper.hpp.
|
protected |
Definition at line 178 of file robots/robot-wrapper.hpp.
|
protected |
Definition at line 184 of file robots/robot-wrapper.hpp.
|
protected |
Definition at line 176 of file robots/robot-wrapper.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar tsid::robots::RobotWrapper::Scalar |
Definition at line 41 of file robots/robot-wrapper.hpp.