#include <Link.h>
Classes | |
struct | ConstraintForce |
Public Types | |
typedef std::vector < ConstraintForce > | ConstraintForceArray |
enum | JointType { FIXED_JOINT, FREE_JOINT, ROTATIONAL_JOINT, SLIDE_JOINT } |
Public Member Functions | |
void | addChild (Link *link) |
Matrix33 | attitude () |
Matrix33 | calcRfromAttitude (const Matrix33 &R) |
void | calcSubMassCM () |
compute sum of m x wc of subtree | |
void | calcSubMassInertia (Matrix33 &subIw) |
compute sum of I of subtree | |
bool | detachChild (Link *link) |
bool | isRoot () |
bool | isValid () |
Link () | |
Link (const Link &link) | |
Matrix33 | segmentAttitude () |
void | setAttitude (const Matrix33 &R) |
void | setSegmentAttitude (const Matrix33 &R) |
void | updateColdetModelPosition () |
virtual | ~Link () |
Public Attributes | |
Vector3 | a |
rotational joint axis (self local) | |
Vector3 | b |
relative position (parent local) | |
Body * | body |
Vector3 | c |
center of mass (self local) | |
Link * | child |
double | climit |
the upper limit of joint current (tlimit = climit x grarRatio x torqueConst) | |
ColdetModelPtr | coldetModel |
ConstraintForceArray | constraintForces |
Vector3 | cv |
dsv * dq (cross velocity term) | |
Vector3 | cw |
dsw * dq (cross velocity term) | |
Vector3 | d |
translation joint axis (self local) | |
double | dd |
Ia*s*s^T. | |
double | ddq |
joint acceleration | |
double | defaultJointValue |
double | dq |
joint velocity | |
Vector3 | dv |
linear acceleration | |
Vector3 | dvo |
derivative of vo | |
Vector3 | dw |
derivative of omega | |
double | encoderPulse |
Vector3 | fext |
external force | |
double | gearEfficiency |
double | gearRatio |
Vector3 | hhv |
top block of Ia*s | |
Vector3 | hhw |
bottom bock of Ia*s | |
Matrix33 | I |
inertia tensor (self local, around c) | |
int | index |
double | Ir |
rotor inertia [kg.m^2] | |
bool | isCrawler |
bool | isHighGainMode |
Matrix33 | Ivv |
top left block of the articulated inertia | |
Matrix33 | Iwv |
bottom left block (transpose of top right block) of the articulated inertia | |
Matrix33 | Iww |
bottm right block of the articulated inertia | |
double | Jm2 |
Equivalent rotor inertia: n^2*Jm [kg.m^2]. | |
int | jointId |
jointId value written in a model file | |
JointType | jointType |
std::vector< Light * > | lights |
lights attached to this link | |
double | llimit |
the lower limit of joint values | |
double | lvlimit |
the lower limit of joint velocities | |
double | m |
mass | |
std::string | name |
Vector3 | p |
position | |
Link * | parent |
Vector3 | pf |
bias force (linear element) | |
Vector3 | ptau |
bias force (torque element) | |
double | q |
joint value | |
Matrix33 | R |
double | rotorResistor |
Matrix33 | Rs |
relative attitude of the link segment (self local) | |
std::vector< Sensor * > | sensors |
sensors attached to this link | |
Link * | sibling |
double | subm |
mass of subtree | |
Vector3 | submwc |
sum of m x wc of subtree | |
Vector3 | sv |
Vector3 | sw |
Vector3 | tauext |
external torque (around the world origin) | |
double | torqueConst |
double | u |
joint torque | |
double | ulimit |
the upper limit of joint values | |
double | uu |
double | uvlimit |
the upper limit of joint velocities | |
Vector3 | v |
linear velocity | |
Vector3 | vo |
translation elements of spacial velocity | |
Vector3 | w |
angular velocity, omega | |
Vector3 | wc |
R * c + p. | |
Private Member Functions | |
Link & | operator= (const Link &link) |
void | putInformation (std::ostream &out) |
void | setBodyIter (Body *body) |
Friends | |
std::ostream & | operator<< (std::ostream &out, hrp::Link &link) |
typedef std::vector<ConstraintForce> hrp::Link::ConstraintForceArray |
enum hrp::Link::JointType |
Link::Link | ( | ) |
Link::Link | ( | const Link & | link | ) |
Link::~Link | ( | ) | [virtual] |
void Link::addChild | ( | Link * | link | ) |
Matrix33 hrp::Link::attitude | ( | ) | [inline] |
Matrix33 hrp::Link::calcRfromAttitude | ( | const Matrix33 & | R | ) | [inline] |
compute sum of m x wc of subtree
void Link::calcSubMassInertia | ( | Matrix33 & | subIw | ) |
compute sum of I of subtree
bool Link::detachChild | ( | Link * | childToRemove | ) |
bool hrp::Link::isRoot | ( | ) | [inline] |
bool hrp::Link::isValid | ( | ) | [inline] |
void Link::putInformation | ( | std::ostream & | out | ) | [private] |
Matrix33 hrp::Link::segmentAttitude | ( | ) | [inline] |
void Link::setBodyIter | ( | Body * | body | ) | [private] |
void hrp::Link::setSegmentAttitude | ( | const Matrix33 & | R | ) | [inline] |
void hrp::Link::updateColdetModelPosition | ( | ) | [inline] |
std::ostream& operator<< | ( | std::ostream & | out, |
hrp::Link & | link | ||
) | [friend] |
double hrp::Link::climit |
double hrp::Link::dd |
double hrp::Link::ddq |
double hrp::Link::defaultJointValue |
double hrp::Link::dq |
double hrp::Link::encoderPulse |
double hrp::Link::gearEfficiency |
double hrp::Link::gearRatio |
double hrp::Link::Ir |
bool hrp::Link::isCrawler |
double hrp::Link::Jm2 |
std::vector<Light *> hrp::Link::lights |
double hrp::Link::llimit |
double hrp::Link::lvlimit |
double hrp::Link::m |
std::string hrp::Link::name |
double hrp::Link::q |
Internal world attitude. In the model computation, it corresponds to the identity matrix when all the joint angles of a robot are zero so that multiplication of local attitdue matrices can be omitted to simplify the computation. If you want to use the original coordinate in the model file, use setAttitude() and attitude() to access.
double hrp::Link::rotorResistor |
std::vector<Sensor *> hrp::Link::sensors |
double hrp::Link::subm |
double hrp::Link::torqueConst |
double hrp::Link::u |
double hrp::Link::ulimit |
double hrp::Link::uu |
double hrp::Link::uvlimit |