#include <World.h>
Classes | |
class | CharacterInfo |
Public Member Functions | |
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 () | |
Protected Attributes | |
pSim * | chain |
std::vector< CharacterInfo > | characters |
std::vector< SDContactPair * > | contact_pairs |
std::vector< Sensor * > | sensors |
Private Member Functions | |
void | _get_all_character_data_sub (Joint *cur, int index, OpenHRP::DynamicsSimulator::LinkDataType type, OpenHRP::DblSequence_out &rdata) |
void | _get_all_sensor_states_sub (Joint *cur, int &count, OpenHRP::SensorState &state) |
void | _set_all_character_data_sub (Joint *cur, int index, OpenHRP::DynamicsSimulator::LinkDataType type, const OpenHRP::DblSequence &wdata) |
void | update_accel_sensor (AccelSensor *as) |
void | update_force_sensor (ForceSensor *fs) |
void | update_rate_gyro_sensor (RateGyroSensor *rgs) |
Private Attributes | |
double | currentTime_ |
fVec3 | g |
bool | isEulerMethod |
int | numRegisteredLinkPairs |
bool | sensorsAreEnabled |
double | timeStep_ |
Definition at line 33 of file server/UtDynamicsSimulator/World.h.
World::World | ( | ) |
Definition at line 68 of file server/UtDynamicsSimulator/World.cpp.
World::~World | ( | ) |
Definition at line 81 of file server/UtDynamicsSimulator/World.cpp.
void World::_get_all_character_data_sub | ( | Joint * | cur, |
int | index, | ||
OpenHRP::DynamicsSimulator::LinkDataType | type, | ||
OpenHRP::DblSequence_out & | rdata | ||
) | [private] |
Definition at line 378 of file server/UtDynamicsSimulator/World.cpp.
void World::_get_all_sensor_states_sub | ( | Joint * | cur, |
int & | count, | ||
OpenHRP::SensorState & | state | ||
) | [private] |
void World::_set_all_character_data_sub | ( | Joint * | cur, |
int | index, | ||
OpenHRP::DynamicsSimulator::LinkDataType | type, | ||
const OpenHRP::DblSequence & | wdata | ||
) | [private] |
Definition at line 429 of file server/UtDynamicsSimulator/World.cpp.
void World::addCharacter | ( | Joint * | rjoint, |
const std::string & | _name, | ||
OpenHRP::LinkInfoSequence_var | links | ||
) |
Definition at line 616 of file server/UtDynamicsSimulator/World.cpp.
void World::addCollisionCheckLinkPair | ( | Joint * | jnt1, |
Joint * | jnt2, | ||
double | staticFriction, | ||
double | slipFriction, | ||
double | epsilon | ||
) |
Definition at line 605 of file server/UtDynamicsSimulator/World.cpp.
int World::addSensor | ( | Joint * | jnt, |
int | sensorType, | ||
int | id, | ||
const std::string | name, | ||
const fVec3 & | _localPos, | ||
const fMat33 & | _localR | ||
) |
Definition at line 312 of file server/UtDynamicsSimulator/World.cpp.
void World::calcCharacterJacobian | ( | const char * | characterName, |
const char * | baseLink, | ||
const char * | targetLink, | ||
fMat & | J | ||
) |
Definition at line 565 of file server/UtDynamicsSimulator/World.cpp.
void World::calcNextState | ( | OpenHRP::CollisionSequence & | corbaCollisionSequence | ) |
Definition at line 146 of file server/UtDynamicsSimulator/World.cpp.
pSim* World::Chain | ( | ) | [inline] |
Definition at line 78 of file server/UtDynamicsSimulator/World.h.
double World::currentTime | ( | void | ) | const [inline] |
Definition at line 63 of file server/UtDynamicsSimulator/World.h.
void World::enableSensors | ( | bool | on | ) |
Definition at line 119 of file server/UtDynamicsSimulator/World.cpp.
Sensor * World::findSensor | ( | const char * | sensorName, |
const char * | charName | ||
) |
Definition at line 325 of file server/UtDynamicsSimulator/World.cpp.
void World::getAllCharacterData | ( | const char * | name, |
OpenHRP::DynamicsSimulator::LinkDataType | type, | ||
OpenHRP::DblSequence_out & | rdata | ||
) |
Definition at line 354 of file server/UtDynamicsSimulator/World.cpp.
void World::getAllCharacterPositions | ( | OpenHRP::CharacterPositionSequence & | all_char_pos | ) |
Definition at line 473 of file server/UtDynamicsSimulator/World.cpp.
void World::getAllSensorStates | ( | OpenHRP::SensorStateSequence & | all_sensor_states | ) |
Definition at line 492 of file server/UtDynamicsSimulator/World.cpp.
const fVec3& World::getGravityAcceleration | ( | ) | [inline] |
Definition at line 66 of file server/UtDynamicsSimulator/World.h.
Definition at line 125 of file server/UtDynamicsSimulator/World.cpp.
int World::numCharacter | ( | ) | [inline] |
Definition at line 108 of file server/UtDynamicsSimulator/World.h.
int World::numJoints | ( | int | index | ) | [inline] |
Definition at line 104 of file server/UtDynamicsSimulator/World.h.
int World::numLinks | ( | int | index | ) | [inline] |
Definition at line 101 of file server/UtDynamicsSimulator/World.h.
int World::numSensors | ( | int | sensorType, |
const char * | charName | ||
) |
Definition at line 339 of file server/UtDynamicsSimulator/World.cpp.
int World::numSensors | ( | ) | [inline] |
Definition at line 87 of file server/UtDynamicsSimulator/World.h.
Joint * World::rootJoint | ( | int | index | ) |
Definition at line 635 of file server/UtDynamicsSimulator/World.cpp.
void World::setAllCharacterData | ( | const char * | name, |
OpenHRP::DynamicsSimulator::LinkDataType | type, | ||
const OpenHRP::DblSequence & | wdata | ||
) |
Definition at line 406 of file server/UtDynamicsSimulator/World.cpp.
void World::setCurrentTime | ( | double | time | ) |
Definition at line 105 of file server/UtDynamicsSimulator/World.cpp.
Definition at line 271 of file server/UtDynamicsSimulator/World.cpp.
Definition at line 111 of file server/UtDynamicsSimulator/World.cpp.
Definition at line 277 of file server/UtDynamicsSimulator/World.cpp.
void World::setTimeStep | ( | double | ts | ) |
Definition at line 99 of file server/UtDynamicsSimulator/World.cpp.
double World::timeStep | ( | void | ) | const [inline] |
Definition at line 60 of file server/UtDynamicsSimulator/World.h.
void World::update_accel_sensor | ( | AccelSensor * | as | ) | [private] |
Definition at line 259 of file server/UtDynamicsSimulator/World.cpp.
void World::update_force_sensor | ( | ForceSensor * | fs | ) | [private] |
Definition at line 237 of file server/UtDynamicsSimulator/World.cpp.
void World::update_rate_gyro_sensor | ( | RateGyroSensor * | rgs | ) | [private] |
Definition at line 254 of file server/UtDynamicsSimulator/World.cpp.
pSim* World::chain [protected] |
Definition at line 113 of file server/UtDynamicsSimulator/World.h.
std::vector<CharacterInfo> World::characters [protected] |
Definition at line 117 of file server/UtDynamicsSimulator/World.h.
std::vector<SDContactPair*> World::contact_pairs [protected] |
Definition at line 114 of file server/UtDynamicsSimulator/World.h.
double World::currentTime_ [private] |
Definition at line 125 of file server/UtDynamicsSimulator/World.h.
Definition at line 151 of file server/UtDynamicsSimulator/World.h.
bool World::isEulerMethod [private] |
Definition at line 153 of file server/UtDynamicsSimulator/World.h.
int World::numRegisteredLinkPairs [private] |
Definition at line 149 of file server/UtDynamicsSimulator/World.h.
std::vector<Sensor*> World::sensors [protected] |
Definition at line 115 of file server/UtDynamicsSimulator/World.h.
bool World::sensorsAreEnabled [private] |
Definition at line 155 of file server/UtDynamicsSimulator/World.h.
double World::timeStep_ [private] |
Definition at line 126 of file server/UtDynamicsSimulator/World.h.