, including all inherited members.
accel_sum | robot | [private] |
addJointGroup(const char *gname, const std::vector< std::string > &jnames) | robot | |
addSensor(Sensor *sensor, int sensorType, int id) | hrp::Body | |
att_sum | robot | [private] |
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 | |
calibrateForceSensorOneStep() | robot | [private] |
calibrateInertiaSensorOneStep() | robot | [private] |
checkEmergency(emg_reason &o_reason, int &o_id) | robot | |
checkJointCommands(const double *i_commands) | robot | |
clearExternalForces() | hrp::Body | |
clearSensorValues() | hrp::Body | |
createLight(Link *link, int lightType, const std::string &name) | hrp::Body | |
createSensor(Link *link, int sensorType, int id, const std::string &name) | hrp::Body | |
default_dgain | robot | [private] |
default_pgain | robot | [private] |
default_tqdgain | robot | [private] |
default_tqpgain | robot | [private] |
dgain | robot | [private] |
disableDisturbanceObserver() | robot | |
EJ_XY | hrp::Body | |
EJ_XYZ | hrp::Body | |
EJ_Z | hrp::Body | |
EMG_FZ enum value | robot | |
EMG_POWER_OFF enum value | robot | |
emg_reason enum name | robot | |
EMG_SERVO_ALARM enum value | robot | |
EMG_SERVO_ERROR enum value | robot | |
enableDisturbanceObserver() | robot | |
extraJoints | hrp::Body | |
ExtraJointType enum name | hrp::Body | |
force_calib_counter | robot | [private] |
force_sum | robot | [private] |
G | robot | [private] |
gain_control() | robot | [private] |
gain_control(int id) | robot | [private] |
gain_counter | robot | [private] |
getDefaultRootPosition(Vector3 &out_p, Matrix33 &out_R) | hrp::Body | |
getJointPath(Link *baseLink, Link *targetLink) | hrp::Body | |
gyro_sum | robot | [private] |
inertia_calib_counter | robot | [private] |
init() | robot | |
init() | robot | |
initializeConfiguration() | hrp::Body | |
initializeJointAngle(const char *name, const char *option) | robot | |
installCustomizer() | hrp::Body | |
installCustomizer(BodyCustomizerInterface *customizerInterface) | hrp::Body | |
isBusy() const | robot | [private] |
isStaticModel() | hrp::Body | |
joint(int id) const | hrp::Body | |
joints() const | hrp::Body | |
lengthDigitalInput() | robot | |
lengthDigitalOutput() | robot | |
lengthOfExtraServoState(int id) | robot | |
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 | |
loadGain() | robot | |
m_accLimit | robot | |
m_calibJointName | robot | [private] |
m_calibOptions | robot | [private] |
m_calibRequested | robot | [private] |
m_commandOld | robot | [private] |
m_dt | robot | [private] |
m_enable_poweroff_check | robot | [private] |
m_fzLimitRatio | robot | |
m_jointGroups | robot | [private] |
m_lLegForceSensorId | robot | [private] |
m_maxZmpError | robot | |
m_pdgainsFilename | robot | [private] |
m_reportedEmergency | robot | [private] |
m_rLegForceSensorId | robot | [private] |
m_servoErrorLimit | robot | |
m_servoOnDelay | robot | |
m_velocityOld | robot | [private] |
modelName() | hrp::Body | |
name() | hrp::Body | |
names2ids(const std::vector< std::string > &i_names, std::vector< int > &o_ids) | robot | [private] |
numBatteries() | robot | |
numJoints() const | hrp::Body | |
numLinks() const | hrp::Body | |
numSensors(int sensorType) const | hrp::Body | |
numSensorTypes() const | hrp::Body | |
numThermometers() | robot | |
old_dgain | robot | [private] |
old_pgain | robot | [private] |
old_tqdgain | robot | [private] |
old_tqpgain | robot | [private] |
oneStep() | robot | |
pgain | robot | [private] |
power(int jid, bool turnon) | robot | |
power(const char *jname, bool turnon) | robot | |
putInformation(std::ostream &out) | hrp::Body | |
readAccelerometer(unsigned int i_rank, double *o_accs) | robot | |
readBatteryState(unsigned int i_rank, double &o_voltage, double &o_current, double &o_soc) | robot | |
readCalibState(int i) | robot | |
readDigitalInput(char *o_din) | robot | |
readDigitalOutput(char *o_dout) | robot | |
readDriverTemperature(int i) | robot | |
readExtraServoState(int id, int *state) | robot | |
readForceSensor(unsigned int i_rank, double *o_forces) | robot | |
readGyroSensor(unsigned int i_rank, double *o_rates) | robot | |
readJointAngles(double *o_angles) | robot | |
readJointCommands(double *o_commands) | robot | |
readJointCommandTorques(double *o_torques) | robot | |
readJointTorques(double *o_torques) | robot | |
readJointVelocities(double *o_velocities) | robot | |
readPDControllerTorques(double *o_torques) | robot | |
readPowerState(int i) | robot | |
readPowerStatus(double &o_voltage, double &o_current) | robot | |
readServoAlarm(int i) | robot | |
readServoState(int i) | robot | |
readThermometer(unsigned int i_rank, double &o_temp) | robot | |
refCounter() | hrp::Referenced | [protected] |
Referenced() | hrp::Referenced | |
removeForceSensorOffset() | robot | |
robot(double dt) | robot | |
robot() | robot | |
rootLink() const | hrp::Body | |
sensor(int sensorType, int sensorId) const | hrp::Body | |
sensor(int id) const | hrp::Body | |
sensor(const std::string &name) const | hrp::Body | |
servo(int jid, bool turnon) | robot | |
servo(const char *jname, bool turnon) | robot | |
setColumnOfMassMatrix(dmatrix &M, int column) | hrp::Body | |
setDefaultRootPosition(const Vector3 &p, const Matrix33 &R) | hrp::Body | |
setDisturbanceObserverGain(double gain) | robot | |
setJointControlMode(const char *i_jname, joint_control_mode mode) | robot | |
setJointInertia(const char *i_jname, double i_mn) | robot | |
setJointInertias(const double *i_mn) | robot | |
setModelName(const std::string &name) | hrp::Body | |
setName(const std::string &name) | hrp::Body | |
setProperty(const char *key, const char *value) | robot | |
setRootLink(Link *link) | hrp::Body | |
setServoErrorLimit(const char *i_jname, double i_limit) | robot | |
setServoErrorLimit(const char *i_jname, double i_limit) | robot | |
setServoGainPercentage(const char *i_jname, double i_percentage) | robot | |
setServoTorqueGainPercentage(const char *i_jname, double i_percentage) | robot | |
setVirtualJointForces() | hrp::Body | |
startForceSensorCalibration() | robot | |
startInertiaSensorCalibration() | robot | |
totalMass() const | hrp::Body | |
tqdgain | robot | [private] |
tqpgain | robot | [private] |
updateLinkColdetModelPositions() | hrp::Body | |
updateLinkTree() | hrp::Body | |
wait_sem | robot | [private] |
writeAccelerationCommands(const double *i_commands) | robot | |
writeDigitalOutput(const char *i_dout) | robot | |
writeDigitalOutputWithMask(const char *i_dout, const char *i_mask) | robot | |
writeJointCommands(const double *i_commands) | robot | |
writeTorqueCommands(const double *i_commands) | robot | |
writeVelocityCommands(const double *i_commands) | robot | |
~Body() | hrp::Body | [virtual] |
~Referenced() | hrp::Referenced | [virtual] |
~robot() | robot | |
~robot() | robot | |