Classes | Public Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
hrp::WorldBase Class Reference

#include <World.h>

Inheritance diagram for hrp::WorldBase:
Inheritance graph
[legend]

Classes

struct  BodyInfo
 
struct  LinkPairKey
 

Public Member Functions

int addBody (BodyPtr body)
 add body to this world More...
 
BodyPtr body (int index)
 get body by index More...
 
BodyPtr body (const std::string &name)
 get body by name 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 Vector3getGravityAcceleration ()
 get gravity acceleration More...
 
std::pair< int, bool > getIndexOfLinkPairs (Link *link1, Link *link2)
 get index of link pairs More...
 
virtual void initialize ()
 initialize this world. This must be called after all bodies are registered. 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 ()
 

Protected Attributes

std::vector< BodyInfobodyInfoArray
 
double currentTime_
 
bool sensorsAreEnabled
 
double timeStep_
 

Private Types

typedef std::map< BodyPtr, intBodyToIndexMap
 
typedef std::map< LinkPairKey, intLinkPairKeyToIndexMap
 
typedef std::map< std::string, intNameToIndexMap
 

Private Member Functions

void updateRangeSensor (RangeSensor *sensor)
 
void updateRangeSensors ()
 

Private Attributes

BodyToIndexMap bodyToIndexMap
 
Vector3 g
 
bool isEulerMethod
 
LinkPairKeyToIndexMap linkPairKeyToIndexMap
 
NameToIndexMap nameToBodyIndexMap
 
int numRegisteredLinkPairs
 

Detailed Description

Definition at line 34 of file hrplib/hrpModel/World.h.

Member Typedef Documentation

typedef std::map<BodyPtr, int> hrp::WorldBase::BodyToIndexMap
private

Definition at line 185 of file hrplib/hrpModel/World.h.

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.

Constructor & Destructor Documentation

WorldBase::WorldBase ( )

Definition at line 30 of file hrplib/hrpModel/World.cpp.

WorldBase::~WorldBase ( )
virtual

Definition at line 43 of file hrplib/hrpModel/World.cpp.

Member Function Documentation

int WorldBase::addBody ( BodyPtr  body)

add body to this world

Parameters
body
Returns
index of the body
Note
This must be called before initialize() is called.

Definition at line 153 of file hrplib/hrpModel/World.cpp.

BodyPtr WorldBase::body ( int  index)

get body by index

Parameters
indexof the body
Returns
body

Definition at line 56 of file hrplib/hrpModel/World.cpp.

BodyPtr WorldBase::body ( const std::string &  name)

get body by name

Parameters
nameof the body
Returns
body

Definition at line 65 of file hrplib/hrpModel/World.cpp.

int WorldBase::bodyIndex ( const std::string &  name)

get index of body by name

Parameters
nameof the body
Returns
index 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.

void WorldBase::clearBodies ( )

clear bodies in this world

Definition at line 166 of file hrplib/hrpModel/World.cpp.

void WorldBase::clearCollisionPairs ( )

clear collision pairs

Definition at line 173 of file hrplib/hrpModel/World.cpp.

double hrp::WorldBase::currentTime ( void  ) const
inline

get current time

Returns
current time[s]

Definition at line 116 of file hrplib/hrpModel/World.h.

void WorldBase::enableSensors ( bool  on)

enable/disable sensor simulation

Parameters
ontrue to enable, false to disable
Note
This must be called before initialize() is called.

Definition at line 93 of file hrplib/hrpModel/World.cpp.

ForwardDynamicsPtr hrp::WorldBase::forwardDynamics ( int  index)
inline

get forward dynamics computation method for body

Parameters
indexindex of the body
Returns
forward dynamics computation method

Definition at line 65 of file hrplib/hrpModel/World.h.

const Vector3& hrp::WorldBase::getGravityAcceleration ( )
inline

get gravity acceleration

Returns
gravity accleration

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

Parameters
link1link1
link2link2
Returns
pair of index and flag. The flag is true if the pair was already registered, false othewise.

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

Returns
the number of bodies

Definition at line 44 of file hrplib/hrpModel/World.h.

void WorldBase::setCurrentTime ( double  tm)

set current time

Parameters
tmcurrent time[s]

Definition at line 81 of file hrplib/hrpModel/World.cpp.

void WorldBase::setEulerMethod ( )

choose euler method for integration

Definition at line 180 of file hrplib/hrpModel/World.cpp.

void WorldBase::setGravityAcceleration ( const Vector3 g)

set gravity acceleration

Parameters
ggravity acceleration[m/s^2]

Definition at line 87 of file hrplib/hrpModel/World.cpp.

void WorldBase::setRungeKuttaMethod ( )

choose runge-kutta method for integration

Definition at line 186 of file hrplib/hrpModel/World.cpp.

void WorldBase::setTimeStep ( double  dt)

set time step

Parameters
dttime step[s]

Definition at line 75 of file hrplib/hrpModel/World.cpp.

double hrp::WorldBase::timeStep ( void  ) const
inline

get time step

Returns
time step[s]

Definition at line 104 of file hrplib/hrpModel/World.h.

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.

Member Data Documentation

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.

LinkPairKeyToIndexMap hrp::WorldBase::linkPairKeyToIndexMap
private

Definition at line 194 of file hrplib/hrpModel/World.h.

NameToIndexMap hrp::WorldBase::nameToBodyIndexMap
private

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.


The documentation for this class was generated from the following files:


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat Apr 13 2019 02:14:32