#include <ODE_Link.h>
Public Attributes | |
dBodyID | bodyId |
hrp::Vector3 | C |
std::vector< dGeomID > | geomIds |
std::vector< int > | indices |
dJointID | odeJointId |
dTriMeshDataID | triMeshDataId |
std::vector< dReal > | vertices |
Public Attributes inherited from hrp::Link | |
Vector3 | a |
rotational joint axis (self local) More... | |
Vector3 | b |
relative position (parent local) More... | |
Body * | body |
Vector3 | c |
center of mass (self local) More... | |
Link * | child |
double | climit |
the upper limit of joint current (tlimit = climit x grarRatio x torqueConst) More... | |
ColdetModelPtr | coldetModel |
ConstraintForceArray | constraintForces |
Vector3 | cv |
dsv * dq (cross velocity term) More... | |
Vector3 | cw |
dsw * dq (cross velocity term) More... | |
Vector3 | d |
translation joint axis (self local) More... | |
double | dd |
Ia*s*s^T. More... | |
double | ddq |
joint acceleration More... | |
double | defaultJointValue |
double | dq |
joint velocity More... | |
Vector3 | dv |
linear acceleration More... | |
Vector3 | dvo |
derivative of vo More... | |
Vector3 | dw |
derivative of omega More... | |
double | encoderPulse |
Vector3 | fext |
external force More... | |
double | gearEfficiency |
double | gearRatio |
Vector3 | hhv |
top block of Ia*s More... | |
Vector3 | hhw |
bottom bock of Ia*s More... | |
Matrix33 | I |
inertia tensor (self local, around c) More... | |
int | index |
double | Ir |
rotor inertia [kg.m^2] More... | |
bool | isCrawler |
bool | isHighGainMode |
Matrix33 | Ivv |
top left block of the articulated inertia More... | |
Matrix33 | Iwv |
bottom left block (transpose of top right block) of the articulated inertia More... | |
Matrix33 | Iww |
bottm right block of the articulated inertia More... | |
double | Jm2 |
Equivalent rotor inertia: n^2*Jm [kg.m^2]. More... | |
int | jointId |
jointId value written in a model file More... | |
JointType | jointType |
std::vector< Light * > | lights |
lights attached to this link More... | |
double | llimit |
the lower limit of joint values More... | |
double | lvlimit |
the lower limit of joint velocities More... | |
double | m |
mass More... | |
std::string | name |
Vector3 | p |
position More... | |
Link * | parent |
Vector3 | pf |
bias force (linear element) More... | |
Vector3 | ptau |
bias force (torque element) More... | |
double | q |
joint value More... | |
Matrix33 | R |
double | rotorResistor |
Matrix33 | Rs |
relative attitude of the link segment (self local) More... | |
std::vector< Sensor * > | sensors |
sensors attached to this link More... | |
Link * | sibling |
double | subm |
mass of subtree More... | |
Vector3 | submwc |
sum of m x wc of subtree More... | |
Vector3 | sv |
Vector3 | sw |
Vector3 | tauext |
external torque (around the world origin) More... | |
double | torqueConst |
double | u |
joint torque More... | |
double | ulimit |
the upper limit of joint values More... | |
double | uu |
double | uvlimit |
the upper limit of joint velocities More... | |
Vector3 | v |
linear velocity More... | |
Vector3 | vo |
translation elements of spacial velocity More... | |
Vector3 | w |
angular velocity, omega More... | |
Vector3 | wc |
R * c + p. More... | |
Additional Inherited Members | |
Public Types inherited from hrp::Link | |
typedef std::vector< ConstraintForce > | ConstraintForceArray |
enum | JointType { FIXED_JOINT, FREE_JOINT, ROTATIONAL_JOINT, SLIDE_JOINT } |
Definition at line 19 of file ODE_Link.h.
void ODE_Link::destroy | ( | ) |
Definition at line 93 of file ODE_Link.cpp.
dReal ODE_Link::getAngle | ( | ) |
Definition at line 32 of file ODE_Link.cpp.
const dReal * ODE_Link::getAngularVel | ( | ) |
Definition at line 57 of file ODE_Link.cpp.
const dReal * ODE_Link::getForce | ( | ) |
Definition at line 77 of file ODE_Link.cpp.
void ODE_Link::getLinearVel | ( | hrp::Vector3 & | v | ) |
Definition at line 61 of file ODE_Link.cpp.
const dReal * ODE_Link::getTorque | ( | ) |
Definition at line 81 of file ODE_Link.cpp.
void ODE_Link::getTransform | ( | hrp::Vector3 & | pos, |
hrp::Matrix33 & | R | ||
) |
Definition at line 12 of file ODE_Link.cpp.
dReal ODE_Link::getVelocity | ( | ) |
Definition at line 41 of file ODE_Link.cpp.
void ODE_Link::setAbsVelocity | ( | hrp::Vector3 & | v, |
hrp::Vector3 & | w | ||
) |
Definition at line 67 of file ODE_Link.cpp.
void ODE_Link::setForce | ( | double | fx, |
double | fy, | ||
double | fz | ||
) |
Definition at line 85 of file ODE_Link.cpp.
void ODE_Link::setTorque | ( | double | fx, |
double | fy, | ||
double | fz | ||
) |
Definition at line 89 of file ODE_Link.cpp.
void ODE_Link::setTorque | ( | dReal | data | ) |
Definition at line 50 of file ODE_Link.cpp.
void ODE_Link::setTransform | ( | const hrp::Vector3 & | pos, |
const hrp::Matrix33 & | R | ||
) |
Definition at line 23 of file ODE_Link.cpp.
dBodyID ODE_Link::bodyId |
Definition at line 39 of file ODE_Link.h.
hrp::Vector3 ODE_Link::C |
Definition at line 47 of file ODE_Link.h.
std::vector<dGeomID> ODE_Link::geomIds |
Definition at line 42 of file ODE_Link.h.
std::vector<int> ODE_Link::indices |
Definition at line 45 of file ODE_Link.h.
dJointID ODE_Link::odeJointId |
Definition at line 40 of file ODE_Link.h.
dTriMeshDataID ODE_Link::triMeshDataId |
Definition at line 43 of file ODE_Link.h.
std::vector<dReal> ODE_Link::vertices |
Definition at line 44 of file ODE_Link.h.