|
void | createPorts (RTC::DataFlowComponentBase *comp) |
|
void | input () |
|
void | output (OpenHRP::RobotState &state) |
|
| RTCBody () |
|
| ~RTCBody () |
|
Public Member Functions inherited from hrp::Body |
void | addSensor (Sensor *sensor, int sensorType, int id) |
|
| Body () |
|
| Body (const Body &org) |
|
void | calcAngularMomentumJacobian (Link *base, dmatrix &H) |
|
Vector3 | calcCM () |
|
void | calcCMJacobian (Link *base, dmatrix &J) |
|
void | calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false) |
|
void | calcInverseDynamics (Link *link, Vector3 &out_f, Vector3 &out_tau) |
|
void | calcMassMatrix (dmatrix &out_M) |
|
double | calcTotalMass () |
|
void | calcTotalMomentum (Vector3 &out_P, Vector3 &out_L) |
|
void | calcTotalMomentumFromJacobian (Vector3 &out_P, Vector3 &out_L) |
|
void | clearExternalForces () |
|
void | clearSensorValues () |
|
Light * | createLight (Link *link, int lightType, const std::string &name) |
|
Sensor * | createSensor (Link *link, int sensorType, int id, const std::string &name) |
|
void | getDefaultRootPosition (Vector3 &out_p, Matrix33 &out_R) |
|
JointPathPtr | getJointPath (Link *baseLink, Link *targetLink) |
|
void | initializeConfiguration () |
|
bool | installCustomizer () |
|
bool | installCustomizer (BodyCustomizerInterface *customizerInterface) |
|
bool | isStaticModel () |
|
Link * | joint (int id) const |
|
const std::vector< Link * > & | joints () const |
|
Light * | light (const std::string &name) |
|
Link * | link (int index) const |
|
Link * | link (const std::string &name) const |
|
const LinkTraverse & | links () const |
|
const LinkTraverse & | linkTraverse () const |
|
const std::string & | modelName () |
|
const std::string & | name () |
|
unsigned int | numJoints () const |
|
unsigned int | numLinks () const |
|
unsigned int | numSensors (int sensorType) const |
|
unsigned int | numSensorTypes () const |
|
void | putInformation (std::ostream &out) |
|
Link * | rootLink () const |
|
Sensor * | sensor (int sensorType, int sensorId) const |
|
TSensor * | sensor (const std::string &name) const |
|
TSensor * | sensor (int id) const |
|
void | setColumnOfMassMatrix (dmatrix &M, int column) |
|
void | setDefaultRootPosition (const Vector3 &p, const Matrix33 &R) |
|
void | setModelName (const std::string &name) |
|
void | setName (const std::string &name) |
|
void | setRootLink (Link *link) |
|
void | setVirtualJointForces () |
|
double | totalMass () const |
|
void | updateLinkColdetModelPositions () |
|
void | updateLinkTree () |
|
virtual | ~Body () |
|
| Referenced () |
|
virtual | ~Referenced () |
|
Definition at line 14 of file RTCBody.h.