#include <World.h>

Classes | |
| struct | BodyInfo |
| struct | LinkPairKey |
Public Member Functions | |
| int | addBody (BodyPtr body) |
| add body to this world | |
| BodyPtr | body (int index) |
| get body by index | |
| BodyPtr | body (const std::string &name) |
| get body by name | |
| int | bodyIndex (const std::string &name) |
| get index of body by name | |
| virtual void | calcNextState () |
| compute forward dynamics and update current state | |
| void | clearBodies () |
| clear bodies in this world | |
| void | clearCollisionPairs () |
| clear collision pairs | |
| double | currentTime (void) const |
| get current time | |
| void | enableSensors (bool on) |
| enable/disable sensor simulation | |
| ForwardDynamicsPtr | forwardDynamics (int index) |
| get forward dynamics computation method for body | |
| const Vector3 & | getGravityAcceleration () |
| get gravity acceleration | |
| std::pair< int, bool > | getIndexOfLinkPairs (Link *link1, Link *link2) |
| get index of link pairs | |
| virtual void | initialize () |
| initialize this world. This must be called after all bodies are registered. | |
| unsigned int | numBodies () |
| get the number of bodies in this world | |
| void | setCurrentTime (double tm) |
| set current time | |
| void | setEulerMethod () |
| choose euler method for integration | |
| void | setGravityAcceleration (const Vector3 &g) |
| set gravity acceleration | |
| void | setRungeKuttaMethod () |
| choose runge-kutta method for integration | |
| void | setTimeStep (double dt) |
| set time step | |
| double | timeStep (void) const |
| get time step | |
| WorldBase () | |
| virtual | ~WorldBase () |
Protected Attributes | |
| std::vector< BodyInfo > | bodyInfoArray |
| double | currentTime_ |
| bool | sensorsAreEnabled |
| double | timeStep_ |
Private Types | |
| typedef std::map< BodyPtr, int > | BodyToIndexMap |
| typedef std::map< LinkPairKey, int > | LinkPairKeyToIndexMap |
| typedef std::map< std::string, int > | NameToIndexMap |
Private Member Functions | |
| void | updateRangeSensor (RangeSensor *sensor) |
| void | updateRangeSensors () |
Private Attributes | |
| BodyToIndexMap | bodyToIndexMap |
| Vector3 | g |
| bool | isEulerMethod |
| LinkPairKeyToIndexMap | linkPairKeyToIndexMap |
| NameToIndexMap | nameToBodyIndexMap |
| int | numRegisteredLinkPairs |
Definition at line 34 of file hrplib/hrpModel/World.h.
typedef std::map<BodyPtr, int> hrp::WorldBase::BodyToIndexMap [private] |
Definition at line 185 of file hrplib/hrpModel/World.h.
typedef std::map<LinkPairKey, int> hrp::WorldBase::LinkPairKeyToIndexMap [private] |
Definition at line 193 of file hrplib/hrpModel/World.h.
typedef std::map<std::string, int> hrp::WorldBase::NameToIndexMap [private] |
Definition at line 182 of file hrplib/hrpModel/World.h.
Definition at line 30 of file hrplib/hrpModel/World.cpp.
| WorldBase::~WorldBase | ( | ) | [virtual] |
Definition at line 43 of file hrplib/hrpModel/World.cpp.
| int WorldBase::addBody | ( | BodyPtr | body | ) |
add body to this world
| body |
Definition at line 153 of file hrplib/hrpModel/World.cpp.
| BodyPtr WorldBase::body | ( | int | index | ) |
get body by index
| index | of the body |
Definition at line 56 of file hrplib/hrpModel/World.cpp.
| BodyPtr WorldBase::body | ( | const std::string & | name | ) |
get body by name
| name | of the body |
Definition at line 65 of file hrplib/hrpModel/World.cpp.
| int WorldBase::bodyIndex | ( | const std::string & | name | ) |
get index of body by name
| name | of the body |
Definition at line 49 of file hrplib/hrpModel/World.cpp.
| void WorldBase::calcNextState | ( | ) | [virtual] |
compute forward dynamics and update current state
Definition at line 135 of file hrplib/hrpModel/World.cpp.
clear bodies in this world
Definition at line 166 of file hrplib/hrpModel/World.cpp.
clear collision pairs
Definition at line 173 of file hrplib/hrpModel/World.cpp.
| double hrp::WorldBase::currentTime | ( | void | ) | const [inline] |
| void WorldBase::enableSensors | ( | bool | on | ) |
enable/disable sensor simulation
| on | true to enable, false to disable |
Definition at line 93 of file hrplib/hrpModel/World.cpp.
| ForwardDynamicsPtr hrp::WorldBase::forwardDynamics | ( | int | index | ) | [inline] |
get forward dynamics computation method for body
| index | index of the body |
Definition at line 65 of file hrplib/hrpModel/World.h.
| const Vector3& hrp::WorldBase::getGravityAcceleration | ( | ) | [inline] |
get gravity acceleration
Definition at line 128 of file hrplib/hrpModel/World.h.
| std::pair< int, bool > WorldBase::getIndexOfLinkPairs | ( | Link * | link1, |
| Link * | link2 | ||
| ) |
get index of link pairs
| link1 | link1 |
| link2 | link2 |
Definition at line 192 of file hrplib/hrpModel/World.cpp.
| void WorldBase::initialize | ( | void | ) | [virtual] |
initialize this world. This must be called after all bodies are registered.
Reimplemented in hrp::World< TConstraintForceSolver >, hrp::World< hrp::ConstraintForceSolver >, and ODE_World.
Definition at line 99 of file hrplib/hrpModel/World.cpp.
| unsigned int hrp::WorldBase::numBodies | ( | ) | [inline] |
get the number of bodies in this world
Definition at line 44 of file hrplib/hrpModel/World.h.
| void WorldBase::setCurrentTime | ( | double | tm | ) |
set current time
| tm | current time[s] |
Definition at line 81 of file hrplib/hrpModel/World.cpp.
choose euler method for integration
Definition at line 180 of file hrplib/hrpModel/World.cpp.
set gravity acceleration
| g | gravity acceleration[m/s^2] |
Definition at line 87 of file hrplib/hrpModel/World.cpp.
choose runge-kutta method for integration
Definition at line 186 of file hrplib/hrpModel/World.cpp.
| void WorldBase::setTimeStep | ( | double | dt | ) |
| double hrp::WorldBase::timeStep | ( | void | ) | const [inline] |
| void WorldBase::updateRangeSensor | ( | RangeSensor * | sensor | ) | [private] |
Definition at line 248 of file hrplib/hrpModel/World.cpp.
| void WorldBase::updateRangeSensors | ( | ) | [private] |
Definition at line 234 of file hrplib/hrpModel/World.cpp.
std::vector<BodyInfo> hrp::WorldBase::bodyInfoArray [protected] |
Definition at line 174 of file hrplib/hrpModel/World.h.
BodyToIndexMap hrp::WorldBase::bodyToIndexMap [private] |
Definition at line 186 of file hrplib/hrpModel/World.h.
double hrp::WorldBase::currentTime_ [protected] |
Definition at line 167 of file hrplib/hrpModel/World.h.
Vector3 hrp::WorldBase::g [private] |
Definition at line 198 of file hrplib/hrpModel/World.h.
bool hrp::WorldBase::isEulerMethod [private] |
Definition at line 200 of file hrplib/hrpModel/World.h.
Definition at line 194 of file hrplib/hrpModel/World.h.
Definition at line 183 of file hrplib/hrpModel/World.h.
int hrp::WorldBase::numRegisteredLinkPairs [private] |
Definition at line 196 of file hrplib/hrpModel/World.h.
bool hrp::WorldBase::sensorsAreEnabled [protected] |
Definition at line 176 of file hrplib/hrpModel/World.h.
double hrp::WorldBase::timeStep_ [protected] |
Definition at line 168 of file hrplib/hrpModel/World.h.