addSensor(Sensor *sensor, int sensorType, int id) | hrp::Body | |
Body() | hrp::Body | |
Body(const Body &org) | hrp::Body | |
bodyInterface() | hrp::Body | static |
calcAngularMomentumJacobian(Link *base, dmatrix &H) | hrp::Body | |
calcCM() | hrp::Body | |
calcCMJacobian(Link *base, dmatrix &J) | hrp::Body | |
calcForwardKinematics(bool calcVelocity=false, bool calcAcceleration=false) | hrp::Body | |
calcInverseDynamics(Link *link, Vector3 &out_f, Vector3 &out_tau) | hrp::Body | |
calcMassMatrix(dmatrix &out_M) | hrp::Body | |
calcTotalMass() | hrp::Body | |
calcTotalMomentum(Vector3 &out_P, Vector3 &out_L) | hrp::Body | |
calcTotalMomentumFromJacobian(Vector3 &out_P, Vector3 &out_L) | hrp::Body | |
clearExternalForces() | hrp::Body | |
clearSensorValues() | hrp::Body | |
createLight(Link *link, int lightType, const std::string &name) | hrp::Body | |
createPorts(RTC::DataFlowComponentBase *comp) | RTCBody | |
createSensor(Link *link, int sensorType, int id, const std::string &name) | hrp::Body | |
EJ_XY | hrp::Body | |
EJ_XYZ | hrp::Body | |
EJ_Z | hrp::Body | |
extraJoints | hrp::Body | |
ExtraJointType enum name | hrp::Body | |
getDefaultRootPosition(Vector3 &out_p, Matrix33 &out_R) | hrp::Body | |
getJointPath(Link *baseLink, Link *targetLink) | hrp::Body | |
initializeConfiguration() | hrp::Body | |
input() | RTCBody | |
installCustomizer() | hrp::Body | |
installCustomizer(BodyCustomizerInterface *customizerInterface) | hrp::Body | |
isStaticModel() | hrp::Body | |
joint(int id) const | hrp::Body | |
joints() const | hrp::Body | |
light(const std::string &name) | hrp::Body | |
link(int index) const | hrp::Body | |
link(const std::string &name) const | hrp::Body | |
links() const | hrp::Body | |
linkTraverse() const | hrp::Body | |
m_acc | RTCBody | private |
m_accOut | RTCBody | private |
m_ddqCmd | RTCBody | private |
m_ddqCmdIn | RTCBody | private |
m_dqCmd | RTCBody | private |
m_dqCmdIn | RTCBody | private |
m_force | RTCBody | private |
m_forceOut | RTCBody | private |
m_highgain | RTCBody | private |
m_pos | RTCBody | private |
m_posOut | RTCBody | private |
m_q | RTCBody | private |
m_qCmd | RTCBody | private |
m_qCmdIn | RTCBody | private |
m_qOut | RTCBody | private |
m_rate | RTCBody | private |
m_rateOut | RTCBody | private |
m_rpy | RTCBody | private |
m_rpyOut | RTCBody | private |
m_tau | RTCBody | private |
m_tauIn | RTCBody | private |
modelName() | hrp::Body | |
name() | hrp::Body | |
numJoints() const | hrp::Body | |
numLinks() const | hrp::Body | |
numSensors(int sensorType) const | hrp::Body | |
numSensorTypes() const | hrp::Body | |
output(OpenHRP::RobotState &state) | RTCBody | |
putInformation(std::ostream &out) | hrp::Body | |
refCounter() | hrp::Referenced | protected |
Referenced() | hrp::Referenced | |
rootLink() const | hrp::Body | |
RTCBody() | RTCBody | |
sensor(int sensorType, int sensorId) const | hrp::Body | |
sensor(int id) const | hrp::Body | |
sensor(const std::string &name) const | hrp::Body | |
setColumnOfMassMatrix(dmatrix &M, int column) | hrp::Body | |
setDefaultRootPosition(const Vector3 &p, const Matrix33 &R) | hrp::Body | |
setModelName(const std::string &name) | hrp::Body | |
setName(const std::string &name) | hrp::Body | |
setRootLink(Link *link) | hrp::Body | |
setVirtualJointForces() | hrp::Body | |
totalMass() const | hrp::Body | |
updateLinkColdetModelPositions() | hrp::Body | |
updateLinkTree() | hrp::Body | |
~Body() | hrp::Body | virtual |
~Referenced() | hrp::Referenced | virtual |
~RTCBody() | RTCBody | |