#include <ODE_World.h>
Classes | |
struct | LinkPair |
Public Types | |
typedef std::vector< LinkPair > | LinkPairArray |
Public Member Functions | |
void | addBody (OpenHRP::BodyInfo_ptr body, const char *name) |
add body to this world More... | |
void | addCollisionPair (OpenHRP::LinkPair &linkPair) |
void | calcNextState (OpenHRP::CollisionSequence &corbaCollisionSequence) |
compute forward dynamics and update current state More... | |
void | clearExternalForces () |
void | getGravityAcceleration (dVector3 &gravity) |
get gravity acceleration More... | |
dJointGroupID | getJointGroupID () |
dSpaceID | getSpaceID () |
dWorldID | getWorldID () |
void | initialize () |
initialize this world. This must be called after all bodies are registered. More... | |
ODE_World () | |
void | setGravityAcceleration (const dVector3 &gravity) |
set gravity acceleration More... | |
void | useInternalCollisionDetector (bool use) |
~ODE_World () | |
Public Member Functions inherited from hrp::WorldBase | |
int | addBody (BodyPtr body) |
add body to this world More... | |
BodyPtr | body (const std::string &name) |
get body by name More... | |
BodyPtr | body (int index) |
get body by index More... | |
int | bodyIndex (const std::string &name) |
get index of body by name More... | |
virtual void | calcNextState () |
compute forward dynamics and update current state More... | |
void | clearBodies () |
clear bodies in this world More... | |
void | clearCollisionPairs () |
clear collision pairs More... | |
double | currentTime (void) const |
get current time More... | |
void | enableSensors (bool on) |
enable/disable sensor simulation More... | |
ForwardDynamicsPtr | forwardDynamics (int index) |
get forward dynamics computation method for body More... | |
const Vector3 & | getGravityAcceleration () |
get gravity acceleration More... | |
std::pair< int, bool > | getIndexOfLinkPairs (Link *link1, Link *link2) |
get index of link pairs More... | |
unsigned int | numBodies () |
get the number of bodies in this world More... | |
void | setCurrentTime (double tm) |
set current time More... | |
void | setEulerMethod () |
choose euler method for integration More... | |
void | setGravityAcceleration (const Vector3 &g) |
set gravity acceleration More... | |
void | setRungeKuttaMethod () |
choose runge-kutta method for integration More... | |
void | setTimeStep (double dt) |
set time step More... | |
double | timeStep (void) const |
get time step More... | |
WorldBase () | |
virtual | ~WorldBase () |
Public Attributes | |
OpenHRP::CollisionSequence | collisions |
LinkPairArray | linkPairs |
Private Member Functions | |
void | updateSensors () |
Private Attributes | |
dJointGroupID | contactgroupId |
dSpaceID | spaceId |
bool | useInternalCollisionDetector_ |
dWorldID | worldId |
Additional Inherited Members | |
Protected Attributes inherited from hrp::WorldBase | |
std::vector< BodyInfo > | bodyInfoArray |
double | currentTime_ |
bool | sensorsAreEnabled |
double | timeStep_ |
Definition at line 68 of file ODE_World.h.
typedef std::vector<LinkPair> ODE_World::LinkPairArray |
Definition at line 122 of file ODE_World.h.
ODE_World::ODE_World | ( | ) |
Definition at line 15 of file ODE_World.cpp.
ODE_World::~ODE_World | ( | ) |
Definition at line 32 of file ODE_World.cpp.
add body to this world
body |
Definition at line 55 of file ODE_World.cpp.
void ODE_World::addCollisionPair | ( | OpenHRP::LinkPair & | linkPair | ) |
Definition at line 64 of file ODE_World.cpp.
void ODE_World::calcNextState | ( | OpenHRP::CollisionSequence & | corbaCollisionSequence | ) |
compute forward dynamics and update current state
Definition at line 104 of file ODE_World.cpp.
void ODE_World::clearExternalForces | ( | ) |
Definition at line 193 of file ODE_World.cpp.
void ODE_World::getGravityAcceleration | ( | dVector3 & | gravity | ) |
|
inline |
Definition at line 114 of file ODE_World.h.
|
inline |
Definition at line 113 of file ODE_World.h.
|
inline |
Definition at line 112 of file ODE_World.h.
|
virtual |
initialize this world. This must be called after all bodies are registered.
Reimplemented from hrp::WorldBase.
Definition at line 173 of file ODE_World.cpp.
set gravity acceleration
g | gravity acceleration[m/s^2] |
Definition at line 45 of file ODE_World.cpp.
|
private |
Definition at line 197 of file ODE_World.cpp.
|
inline |
Definition at line 106 of file ODE_World.h.
OpenHRP::CollisionSequence ODE_World::collisions |
Definition at line 116 of file ODE_World.h.
|
private |
Definition at line 128 of file ODE_World.h.
LinkPairArray ODE_World::linkPairs |
Definition at line 123 of file ODE_World.h.
|
private |
Definition at line 127 of file ODE_World.h.
|
private |
Definition at line 130 of file ODE_World.h.
|
private |
Definition at line 126 of file ODE_World.h.