#include <World.h>
|
void | addCharacter (Joint *rjoint, const std::string &_name, OpenHRP::LinkInfoSequence_var links) |
|
void | addCollisionCheckLinkPair (Joint *jnt1, Joint *jnt2, double staticFriction, double slipFriction, double epsilon) |
|
int | addSensor (Joint *jnt, int sensorType, int id, const std::string name, const fVec3 &_localPos, const fMat33 &_localR) |
|
void | calcCharacterJacobian (const char *characterName, const char *baseLink, const char *targetLink, fMat &J) |
|
void | calcNextState (OpenHRP::CollisionSequence &corbaCollisionSequence) |
|
pSim * | Chain () |
|
void | clearCollisionPairs () |
|
double | currentTime (void) const |
|
void | enableSensors (bool on) |
|
Sensor * | findSensor (const char *sensorName, const char *charName) |
|
void | getAllCharacterData (const char *name, OpenHRP::DynamicsSimulator::LinkDataType type, OpenHRP::DblSequence_out &rdata) |
|
void | getAllCharacterPositions (OpenHRP::CharacterPositionSequence &all_char_pos) |
|
void | getAllSensorStates (OpenHRP::SensorStateSequence &all_sensor_states) |
|
const fVec3 & | getGravityAcceleration () |
|
void | initialize () |
|
int | numCharacter () |
|
int | numJoints (int index) |
|
int | numLinks (int index) |
|
int | numSensors (int sensorType, const char *charName) |
|
int | numSensors () |
|
Joint * | rootJoint (int index) |
|
void | setAllCharacterData (const char *name, OpenHRP::DynamicsSimulator::LinkDataType type, const OpenHRP::DblSequence &wdata) |
|
void | setCurrentTime (double) |
|
void | setEulerMethod () |
|
void | setGravityAcceleration (const fVec3 &g) |
|
void | setRungeKuttaMethod () |
|
void | setTimeStep (double) |
|
double | timeStep (void) const |
|
| World () |
|
| ~World () |
|
◆ World()
◆ ~World()
◆ _get_all_character_data_sub()
void World::_get_all_character_data_sub |
( |
Joint * |
cur, |
|
|
int |
index, |
|
|
OpenHRP::DynamicsSimulator::LinkDataType |
type, |
|
|
OpenHRP::DblSequence_out & |
rdata |
|
) |
| |
|
private |
◆ _get_all_sensor_states_sub()
void World::_get_all_sensor_states_sub |
( |
Joint * |
cur, |
|
|
int & |
count, |
|
|
OpenHRP::SensorState & |
state |
|
) |
| |
|
private |
◆ _set_all_character_data_sub()
void World::_set_all_character_data_sub |
( |
Joint * |
cur, |
|
|
int |
index, |
|
|
OpenHRP::DynamicsSimulator::LinkDataType |
type, |
|
|
const OpenHRP::DblSequence & |
wdata |
|
) |
| |
|
private |
◆ addCharacter()
void World::addCharacter |
( |
Joint * |
rjoint, |
|
|
const std::string & |
_name, |
|
|
OpenHRP::LinkInfoSequence_var |
links |
|
) |
| |
◆ addCollisionCheckLinkPair()
void World::addCollisionCheckLinkPair |
( |
Joint * |
jnt1, |
|
|
Joint * |
jnt2, |
|
|
double |
staticFriction, |
|
|
double |
slipFriction, |
|
|
double |
epsilon |
|
) |
| |
◆ addSensor()
◆ calcCharacterJacobian()
void World::calcCharacterJacobian |
( |
const char * |
characterName, |
|
|
const char * |
baseLink, |
|
|
const char * |
targetLink, |
|
|
fMat & |
J |
|
) |
| |
◆ calcNextState()
void World::calcNextState |
( |
OpenHRP::CollisionSequence & |
corbaCollisionSequence | ) |
|
◆ Chain()
◆ clearCollisionPairs()
void World::clearCollisionPairs |
( |
| ) |
|
◆ currentTime()
double World::currentTime |
( |
void |
| ) |
const |
|
inline |
◆ enableSensors()
void World::enableSensors |
( |
bool |
on | ) |
|
◆ findSensor()
◆ getAllCharacterData()
void World::getAllCharacterData |
( |
const char * |
name, |
|
|
OpenHRP::DynamicsSimulator::LinkDataType |
type, |
|
|
OpenHRP::DblSequence_out & |
rdata |
|
) |
| |
◆ getAllCharacterPositions()
void World::getAllCharacterPositions |
( |
OpenHRP::CharacterPositionSequence & |
all_char_pos | ) |
|
◆ getAllSensorStates()
void World::getAllSensorStates |
( |
OpenHRP::SensorStateSequence & |
all_sensor_states | ) |
|
◆ getGravityAcceleration()
◆ initialize()
◆ numCharacter()
int World::numCharacter |
( |
| ) |
|
|
inline |
◆ numJoints()
int World::numJoints |
( |
int |
index | ) |
|
|
inline |
◆ numLinks()
int World::numLinks |
( |
int |
index | ) |
|
|
inline |
◆ numSensors() [1/2]
int World::numSensors |
( |
int |
sensorType, |
|
|
const char * |
charName |
|
) |
| |
◆ numSensors() [2/2]
int World::numSensors |
( |
| ) |
|
|
inline |
◆ rootJoint()
◆ setAllCharacterData()
void World::setAllCharacterData |
( |
const char * |
name, |
|
|
OpenHRP::DynamicsSimulator::LinkDataType |
type, |
|
|
const OpenHRP::DblSequence & |
wdata |
|
) |
| |
◆ setCurrentTime()
void World::setCurrentTime |
( |
double |
time | ) |
|
◆ setEulerMethod()
void World::setEulerMethod |
( |
| ) |
|
◆ setGravityAcceleration()
◆ setRungeKuttaMethod()
void World::setRungeKuttaMethod |
( |
| ) |
|
◆ setTimeStep()
void World::setTimeStep |
( |
double |
ts | ) |
|
◆ timeStep()
double World::timeStep |
( |
void |
| ) |
const |
|
inline |
◆ update_accel_sensor()
◆ update_force_sensor()
◆ update_rate_gyro_sensor()
◆ chain
◆ characters
◆ contact_pairs
◆ currentTime_
double World::currentTime_ |
|
private |
◆ isEulerMethod
bool World::isEulerMethod |
|
private |
◆ numRegisteredLinkPairs
int World::numRegisteredLinkPairs |
|
private |
◆ sensors
std::vector<Sensor*> World::sensors |
|
protected |
◆ sensorsAreEnabled
bool World::sensorsAreEnabled |
|
private |
◆ timeStep_
The documentation for this class was generated from the following files: