World Class Reference

The simulation world holds the world elements and handles their static and dynamic interactions. More...

#include <world.h>

List of all members.

Signals

void dynamicsError (const char *errMsg)
 Signal a dynamics error has occured with an error string.
void dynamicStepTaken ()
 Signal that a dynamic step has been completed.
void graspsUpdated ()
 Signal that all grasps have been updated.
void handRemoved ()
 Signal that a hand was removed from the world.
void handSelectionChanged ()
 Signal we want have changed the currently selected hand from within the code.
void numElementsChanged ()
 Signal that the number of world elements has changed.
void selectionsChanged ()
 Signal that selections have changed.
void tendonDetailsChanged ()
 Signal that the selected tendon's status has changed.
void tendonSelectionChanged ()
 Signal that a tendon has been (de)selected.

Public Member Functions

void addBody (Body *body)
 Adds an already populated body to the world, but not to collision detection system.
void addElementToSceneGraph (WorldElement *e)
 Adds back to the scene graph an element that has been removed.
void addLink (Link *newLink)
 Links are loaded in during the robot load method, but are added to the world with this routine.
void addRobot (Robot *robot, bool addToScene=true)
 Adds an already populated robot to the world,and possibly to the scene graph.
bool collisionsAreOff (WorldElement *e1=NULL, WorldElement *e2=NULL)
 Check if collisions are enabled for a world element (robot or body).
int computeNewVelocities (double timeStep)
 Calls the dynamics routine to build and solve the LCP to find the velocities of the bodies.
void deselectAll ()
 Deselects all currently selected world elements.
void deselectElement (WorldElement *e)
 Removes the worldElement pointed to by e from the list of selected elements.
void deselectTendon ()
 deselect tendon
void destroyElement (WorldElement *e, bool deleteElement=true)
 Removes the element pointed to by e from the world.
bool dynamicsAreOn () const
 Returns whether dynamics are currently running or not.
void emitGraspsUpdated ()
 Emits the signal that informs that grasps have been updated.
void findAllContacts ()
 Finds all the contacts occuring in the world.
void findContacts (Body *b)
 Finds all contacts occurring on body b.
void findContacts (CollisionReport &colReport)
 Finds every contact occurring between the pairs of bodies listed in the colReport.
void FindRegion (const Body *body, position point, vec3 normal, double radius, Neighborhood *neighborhood)
 Finds a region around a given point on a body through the collision detection system.
ContactData findVirtualContact (Link *link, Body *object)
 Helper function that finds the closest point on a link to an object.
void findVirtualContacts (Hand *hand, Body *object)
 Sets up virtual contacts on all links at the closest points to a given body.
BodygetBody (int i) const
 Returns a pointer to the i-th body defined in this world.
void getBvs (Body *b, int depth, std::vector< BoundingBox > *bvs)
 Returns the bounding boxes from the collision detection bounding box hierarchy of a body.
double getCOF (int mat1, int mat2)
 Returns the static coefficient of friction between two materials.
CollisionInterfacegetCollisionInterface ()
 Returns the collision interface being used.
int getCollisionReport (CollisionReport *colReport, const std::vector< Body * > *interestList=NULL)
 Queries the collision detection system for a report of which pairs of bodies are colliding.
HandgetCurrentHand () const
 Returns a pointer to the hand that is the focus of menu commands etc.
int getCurrentHandNumberTendons ()
 returns the number of tendons in the currently selected hand
double getDist (Body *b1, Body *b2, position &p1, position &p2)
 Returns the minimum distance in mm between the two bodies as well as the points on the bodies that are closest.
double getDist (WorldElement *e1, WorldElement *e2)
 Returns the minimum distance in mm between the two bodies; deprecated, use version on world elements.
GraspableBodygetGB (int i) const
 Returns a pointer to the i-th graspable body defined in this world.
HandgetHand (int i) const
 Returns a pointer to the i-th hand defined in this world.
SoSeparator * getIVRoot () const
 Returns the root of the Inventor scene graph for this world.
double getKCOF (int mat1, int mat2)
 Returns the kinetic coefficient of friction between two materials.
int getMaterialIdx (const QString &matName) const
 Returns the material index of the material named by matName.
QString getMaterialName (int i) const
 Returns the name of the material with index i.
int getNumBodies () const
 Returns the number of bodies in this world.
int getNumGB () const
 Returns the number of graspable bodies in this world.
int getNumHands () const
 Returns the number of hands in this world.
int getNumMaterials () const
 Returns the number of materials defined in this world.
int getNumRobots () const
 Returns the number of robots in this world.
int getNumSelectedBodies () const
 Returns the number of selected bodies.
int getNumSelectedBodyElements () const
 Returns the number of selected body elements.
int getNumSelectedElements () const
 Returns the number of selected world elements.
int getNumSelectedRobotElements () const
 Returns the number of selected robot elements.
RobotgetRobot (int i) const
 Returns a pointer to the i-th robot defined in this world.
BodygetSelectedBody (int i) const
 Returns a pointer to the i-th selected body in the world.
const std::list< WorldElement * > & getSelectedElementList () const
 Returns a list of pointers to the currently selected world elements.
QString getSelectedHandTendonName (int i)
 returns the name of the i-th tendon of the currently selected hand
TendongetSelectedTendon ()
 Returns the currently selected tendond.
double getTimeStep () const
 Returns the default timestep for this world.
double getWorldTime () const
 Returns the current simulation time for this world.
BodyimportBody (QString bodyType, QString filename)
 Creates a new body of type bodyType, then calls the load routine of that body.
BodyimportBodyFromXml (QString bodyType, const TiXmlElement *child, QString rootPath)
 Creates a new body of type bodyType, then calls the loadFromXml routine of that body.
RobotimportRobot (QString filename)
 Creates a robot, loads it from a file and adds it to the world.
bool isSelected (WorldElement *e) const
 Returns whether the world element pointed to by e is currently selected or not.
int load (const QString &filename)
 Loads the saved world from the file in filename.
int loadFromXml (const TiXmlElement *root, QString rootPath)
 Loads the saved world from the XML file in filename.
DynamicBodymakeBodyDynamic (Body *b, double mass)
 Creates a new dynamic body from the data in the body pointed to by b.
double moveDynamicBodies (double timeStep)
 Moves all dynamic bodies based on their velocity and the length of the current timestep.
bool noCollision (WorldElement *e=NULL)
 Answers true if there are no collisions in the world, potentially involving a specified element.
vec3 pointDistanceToBody (position p, Body *b, vec3 *normal=NULL)
 Computes the distance between a point and a body.
void popDynamicState ()
 Restores the most recent dynamic state of each dynamic body by popping the state of each body's local stack.
void pushDynamicState ()
 Calls upon each dynamic body to save its current dynamic state to the top of its stack of states.
bool queryTendonSelected ()
 query whether a tendon is selected or not
void removeElementFromSceneGraph (WorldElement *e)
 Removes from the scene graph an element that is already part of this world.
void removeRobot (Robot *robot)
 Removes the robot pointed to by robot from the world, then deletes it.
void resetDynamics ()
 Resets dynamic simulation. Clears the dynamic stack, fixes all robot bases.
void resetDynamicWrenches ()
 Resets the external wrench accumulator for all the dynamic bodies.
bool robotCollisionsAreOff (Robot *r, WorldElement *e)
 Checks if collision between an entire robot and another element are on.
int save (const QString &filename)
 Save the current state of the world to a file.
void selectElement (WorldElement *e)
 Adds the worldElement pointed to by e to the list of selected elements.
void selectTendon (int i)
 Sets the selected tendon, receives an index into the selected hand's list of tendons.
void selectTendon (Tendon *t)
 Set selected tendon.
void setCurrentHand (Hand *hand)
 Called when the user selects a new hand from the drop down menu.
void setDefaults ()
 Sets all world settings to their original default values.
void setModified ()
 Sets the world modified flag. Should be done when a change has since the last save.
bool softContactsAreOn ()
 Returns whether soft contacts are on.
void stepDynamics ()
 One complete step of the dynamics simulation.
void tendonChange ()
 signals that a tendon has changed status, we need to update the tendon status bar
void toggleAllCollisions (bool on)
 Turns the collision detection system on or off.
void toggleCollisions (bool on, WorldElement *e1, WorldElement *e2=NULL)
 Toggle collisions for a world element (robot or body).
void turnOffDynamics ()
 Stops the dynamic simulation process.
void turnOnDynamics ()
 Starts the dynamic simulation for this world.
void updateGrasps ()
 Updates the grasp for any hand that has had contacts change since its grasp was last updated.
bool wasModified () const
 Returns whether this world has been modified since the last save.
 World (QObject *parent=0, const char *name=0, IVmgr *mgr=NULL)
 public constructor
 ~World ()
 Saves the current user settings in the registry and clears the world.

Protected Member Functions

void readSettings ()
 Reads the user preferences for the world settings. Under.
void saveSettings ()
 Saves the user preferences for the world settings.

Static Protected Member Functions

static void dynamicsCB (void *data, SoSensor *sensor)
 Static callback routine for the dynamic operations idle sensor.

Protected Attributes

bool allCollisionsOFF
 A flag to determine if collions checking is on or off.
std::vector< Body * > bodyVec
 A vector of pointers to ALL of the bodies in the world.
double ** cofTable
 A numMaterials x numMaterials array of static coefficient of friction values.
HandcurrentHand
 Keeps track of which hand is currently the focus of menu commands.
bool dynamicsOn
 A flag to determine whether dynamics is currently being used or not.
double dynamicsTimeStep
 The length of the default dynamics time step.
std::vector< GraspableBody * > GBVec
 A vector of pointers to the graspable bodies in the world.
std::vector< Hand * > handVec
 A vector of pointers to the hands defined within this world.
SoIdleSensor * idleSensor
 A pointer to the Inventor idle sensor that is used when dynamics is on.
bool isTendonSelected
 keeps track is a tendon is selected or not
SoSeparator * IVRoot
 A pointer to the root of the world's Inventor scene graph.
double ** kcofTable
 A numMaterials x numMaterials array of kinetic coefficient of friction values.
std::vector< QString > materialNames
 A vector of strings, one for each material name.
CollisionInterfacemCollisionInterface
 A pointer to the collision detection instance.
bool modified
 Keeps track of whether the world has been modified since the last save.
IVmgrmyIVmgr
 Pointer to the IVmgr who controls the simulation.
int numBodies
 The number of bodies currently in this world.
int numGB
 The number of graspable bodies currently in this world.
int numHands
 The number of hands currently in this world.
int numMaterials
 The number of materials defined within this world.
int numRobots
 The number of robots currently in this world.
int numSelectedBodies
 The number of currently selected bodies.
int numSelectedBodyElements
 The number of currently selected body elements.
int numSelectedElements
 The number of currently selected elements.
int numSelectedRobotElements
 The number of currently selected body elements.
std::vector< Robot * > robotVec
 A vector of pointers to the robots defined within this world.
std::vector< Body * > selectedBodyVec
 A vector of pointers to the currently selected bodies.
std::list< WorldElement * > selectedElementList
 A list of pointers to the currently selected worldElements.
TendonselectedTendon
 pointer to selected tendon
bool softContactsON
 Turns on or off soft contacts, needs a switch in the Iv environment.
double worldTime
 Keeps track of the current simulation time.

Friends

class Body
class DynamicBody
class MainWindow

Detailed Description

The simulation world holds the world elements and handles their static and dynamic interactions.

A world object keeps track of all of the world elements (bodies and robots) contained within it. It allows collisions to be turned on or off, completely, for a single body, or just between a pair of bodies. It has several parameters that effect body interactions such as the table of coefficient of friction tables. The world also contains methods advance the dynamic simulation of body motions within the world. The state of a world may be written out to a simple text file which may be reloaded later.

Definition at line 87 of file world.h.


Constructor & Destructor Documentation

World::World ( QObject *  parent = 0,
const char *  name = 0,
IVmgr mgr = NULL 
)

public constructor

Prepares an empty world. mgr is the instance of the inventor manager that will handle all user interaction. Also initialized collision detection system and reads in global settings such as friction coefficients

Definition at line 109 of file world.cpp.

World::~World (  ) 

Saves the current user settings in the registry and clears the world.

Saves the global settings and parameters and deletes the world along with all the objects that populate it.

Definition at line 156 of file world.cpp.


Member Function Documentation

void World::addBody ( Body newBody  ) 

Adds an already populated body to the world, but not to collision detection system.

Adds to this world a body that is already created, initialized and somehow populated. This usually means a body obtained by loading from a file or cloning another body. It does NOT add the new body to the collision detection system, it is the caller's responsability to do that. Also does not initialize dynamics.

Definition at line 886 of file world.cpp.

void World::addElementToSceneGraph ( WorldElement e  ) 

Adds back to the scene graph an element that has been removed.

Adds an element to the Scene Graph; the element must already be part of the world. Used when removeElementFromSceneGraph has previously been called on this element.

Definition at line 1049 of file world.cpp.

void World::addLink ( Link newLink  ) 

Links are loaded in during the robot load method, but are added to the world with this routine.

Adds a robot link. No need to add it to scene graph, since the robot will add it to its own tree. The robot will also init dynamics and add the link to collision detection.

Definition at line 910 of file world.cpp.

void World::addRobot ( Robot robot,
bool  addToScene = true 
)

Adds an already populated robot to the world,and possibly to the scene graph.

Adds to this world a robot that is already created, initialized and somehow populated. This usually means a robot obtained by loading from a file or cloning another body. It only adds the new robot to the scene graph of addToScene is true. Can be used when robots are clones and clones are set to work, but we don't necessarily want to see them.

Collisions between links in the same chain are always disables, as geometry files are usually imperfect and as joints move, the meshes then to hit each other at the joints, which would make the robot unusable.

Definition at line 976 of file world.cpp.

bool World::collisionsAreOff ( WorldElement e1 = NULL,
WorldElement e2 = NULL 
)

Check if collisions are enabled for a world element (robot or body).

Checks whether collisions are off. Options for passing arguments are the same as for toggleCollisions.

Definition at line 1271 of file world.cpp.

int World::computeNewVelocities ( double  timeStep  ) 

Calls the dynamics routine to build and solve the LCP to find the velocities of the bodies.

Asks the dynamics engine to compute the velocities of all bodies at the current time step. These will be used in the next time step when the bodies are moved by World::moveDynamicBodies.

The bodies are separated into "islands" of bodies connected by contacts or joints. Two dynamic bodies are connected if they share a contact or a joint. Then for each island, this calls the iterate dynamics routine to build and solve the LCP to find the velocities of all the bodies in the next iteration.

Definition at line 1979 of file world.cpp.

void World::deselectAll (  ) 

Deselects all currently selected world elements.

Clears the list of selected element and deselects all

Definition at line 1183 of file world.cpp.

void World::deselectElement ( WorldElement e  ) 

Removes the worldElement pointed to by e from the list of selected elements.

Deselects a world element. If the element is a Robot, also deselects all of its links, plus the base.

Definition at line 1152 of file world.cpp.

void World::deselectTendon (  ) 

deselect tendon

Definition at line 2219 of file world.cpp.

void World::destroyElement ( WorldElement e,
bool  deleteElement = true 
)

Removes the element pointed to by e from the world.

Removes a world element (a robot or any kind of body) from the World. Also removes it from the scene graph and the collision detection system. If deleteElement is true, it also deletes it at the end. If it is a graspable body and there is a grasp that references it, it associates the grasp with the first GB or NULL if none are left.

Definition at line 404 of file world.cpp.

bool World::dynamicsAreOn (  )  const [inline]

Returns whether dynamics are currently running or not.

Definition at line 332 of file world.h.

void World::dynamicsCB ( void *  data,
SoSensor *  sensor 
) [static, protected]

Static callback routine for the dynamic operations idle sensor.

Definition at line 1744 of file world.cpp.

void World::dynamicsError ( const char *  errMsg  )  [signal]

Signal a dynamics error has occured with an error string.

Definition at line 108 of file moc_world.cpp.

void World::dynamicStepTaken (  )  [signal]

Signal that a dynamic step has been completed.

Definition at line 102 of file moc_world.cpp.

void World::emitGraspsUpdated (  )  [inline]

Emits the signal that informs that grasps have been updated.

Definition at line 482 of file world.h.

void World::findAllContacts (  ) 

Finds all the contacts occuring in the world.

Finds and adds all the contacts between any two bodies in the world. A pair of contact objects is created for each contact and are added to the individual bodies that are in contact.

Definition at line 1643 of file world.cpp.

void World::findContacts ( Body b  ) 

Finds all contacts occurring on body b.

Finds all the contact on body b. A pair of contact objects is created for each contact and are added to the individual bodies that are in contact.

Definition at line 1626 of file world.cpp.

void World::findContacts ( CollisionReport colReport  ) 

Finds every contact occurring between the pairs of bodies listed in the colReport.

Finds all the contacts between the bodies listed in the colReport. Usually, the colReport is populated by the caller, based on a set of bodies that were in collision before, but now are assumed to be out of collision and potentially just touching.

A contact occurs when bodies are separated by a distance less than the contact threshold. This routine uses the collision detection system to find the points of contact between each body and at each one creates a pair of contact objects which are added to the individual bodies.

Definition at line 1580 of file world.cpp.

void World::FindRegion ( const Body body,
position  point,
vec3  normal,
double  radius,
Neighborhood neighborhood 
)

Finds a region around a given point on a body through the collision detection system.

Takes a point and sends it to the collision detection system to find the neighborhood of that point on a body, used in soft contacts for the input for the paraboloid fitter.

Definition at line 1665 of file world.cpp.

ContactData World::findVirtualContact ( Link link,
Body object 
)

Helper function that finds the closest point on a link to an object.

Definition at line 1540 of file world.cpp.

void World::findVirtualContacts ( Hand hand,
Body object 
)

Sets up virtual contacts on all links at the closest points to a given body.

Definition at line 1517 of file world.cpp.

Body* World::getBody ( int  i  )  const [inline]

Returns a pointer to the i-th body defined in this world.

Definition at line 311 of file world.h.

void World::getBvs ( Body b,
int  depth,
std::vector< BoundingBox > *  bvs 
)

Returns the bounding boxes from the collision detection bounding box hierarchy of a body.

Definition at line 1427 of file world.cpp.

double World::getCOF ( int  mat1,
int  mat2 
) [inline]

Returns the static coefficient of friction between two materials.

Definition at line 293 of file world.h.

CollisionInterface* World::getCollisionInterface (  )  [inline]

Returns the collision interface being used.

Definition at line 471 of file world.h.

int World::getCollisionReport ( CollisionReport colReport,
const std::vector< Body * > *  interestList = NULL 
)

Queries the collision detection system for a report of which pairs of bodies are colliding.

Returns a full collision report for the bodies in the interestList. Check collision interface documentation for details on what the report contains. If interestList is NULL, is returns a collision report for all the bodies in the world.

Definition at line 1414 of file world.cpp.

Hand* World::getCurrentHand (  )  const [inline]

Returns a pointer to the hand that is the focus of menu commands etc.

Definition at line 329 of file world.h.

int World::getCurrentHandNumberTendons (  ) 

returns the number of tendons in the currently selected hand

Definition at line 2228 of file world.cpp.

double World::getDist ( Body b1,
Body b2,
position p1,
position p2 
)

Returns the minimum distance in mm between the two bodies as well as the points on the bodies that are closest.

Returns the distance between two bodies b1 and b2 and sets p1 and p2 to the locations of the two points, one on each body, that are closest to each other

Definition at line 1510 of file world.cpp.

double World::getDist ( WorldElement e1,
WorldElement e2 
)

Returns the minimum distance in mm between the two bodies; deprecated, use version on world elements.

Returns the minimum distance in mm between the two world elements

Returns the distance between two bodies b1 and b2 Deprecated by version below which runs of more general world elements

Returns the distance between two world elements. If one (or both) are robots, will compute the smallest distance between all links of the robot (plus the palm) and the other element.

Definition at line 1467 of file world.cpp.

GraspableBody* World::getGB ( int  i  )  const [inline]

Returns a pointer to the i-th graspable body defined in this world.

Definition at line 314 of file world.h.

Hand* World::getHand ( int  i  )  const [inline]

Returns a pointer to the i-th hand defined in this world.

Definition at line 317 of file world.h.

SoSeparator* World::getIVRoot (  )  const [inline]

Returns the root of the Inventor scene graph for this world.

Definition at line 308 of file world.h.

double World::getKCOF ( int  mat1,
int  mat2 
) [inline]

Returns the kinetic coefficient of friction between two materials.

Definition at line 296 of file world.h.

int World::getMaterialIdx ( const QString &  matName  )  const

Returns the material index of the material named by matName.

Returns the material id of a material with name matName

Definition at line 186 of file world.cpp.

QString World::getMaterialName ( int  i  )  const [inline]

Returns the name of the material with index i.

Definition at line 251 of file world.h.

int World::getNumBodies (  )  const [inline]

Returns the number of bodies in this world.

Definition at line 233 of file world.h.

int World::getNumGB (  )  const [inline]

Returns the number of graspable bodies in this world.

Definition at line 236 of file world.h.

int World::getNumHands (  )  const [inline]

Returns the number of hands in this world.

Definition at line 242 of file world.h.

int World::getNumMaterials (  )  const [inline]

Returns the number of materials defined in this world.

Definition at line 245 of file world.h.

int World::getNumRobots (  )  const [inline]

Returns the number of robots in this world.

Definition at line 239 of file world.h.

int World::getNumSelectedBodies (  )  const [inline]

Returns the number of selected bodies.

Definition at line 263 of file world.h.

int World::getNumSelectedBodyElements (  )  const [inline]

Returns the number of selected body elements.

Definition at line 254 of file world.h.

int World::getNumSelectedElements (  )  const [inline]

Returns the number of selected world elements.

Definition at line 260 of file world.h.

int World::getNumSelectedRobotElements (  )  const [inline]

Returns the number of selected robot elements.

Definition at line 257 of file world.h.

Robot* World::getRobot ( int  i  )  const [inline]

Returns a pointer to the i-th robot defined in this world.

Definition at line 320 of file world.h.

Body* World::getSelectedBody ( int  i  )  const [inline]

Returns a pointer to the i-th selected body in the world.

Definition at line 266 of file world.h.

const std::list<WorldElement *>& World::getSelectedElementList (  )  const [inline]

Returns a list of pointers to the currently selected world elements.

Definition at line 326 of file world.h.

QString World::getSelectedHandTendonName ( int  i  ) 

returns the name of the i-th tendon of the currently selected hand

Definition at line 2238 of file world.cpp.

Tendon* World::getSelectedTendon (  )  [inline]

Returns the currently selected tendond.

Definition at line 272 of file world.h.

double World::getTimeStep (  )  const [inline]

Returns the default timestep for this world.

Definition at line 302 of file world.h.

double World::getWorldTime (  )  const [inline]

Returns the current simulation time for this world.

Definition at line 299 of file world.h.

void World::graspsUpdated (  )  [signal]

Signal that all grasps have been updated.

Definition at line 133 of file moc_world.cpp.

void World::handRemoved (  )  [signal]

Signal that a hand was removed from the world.

Definition at line 127 of file moc_world.cpp.

void World::handSelectionChanged (  )  [signal]

Signal we want have changed the currently selected hand from within the code.

Definition at line 139 of file moc_world.cpp.

Body * World::importBody ( QString  bodyType,
QString  filename 
)

Creates a new body of type bodyType, then calls the load routine of that body.

Imports a body which is loaded from a file. must be a class name from the Body hierarchy (e.g. "Body", "DynamicBody", etc). filename is the complete path to the file containing the body. The new body is created, loaded from the file, initialized, and added to the collision detection and scene graph.

Definition at line 852 of file world.cpp.

Body * World::importBodyFromXml ( QString  bodyType,
const TiXmlElement child,
QString  rootPath 
)

Creates a new body of type bodyType, then calls the loadFromXml routine of that body.

Imports a body which is loaded from a xml file. must be a class name from the Body hierarchy (e.g. "Body", "DynamicBody", etc). rootPath and child are parsed to loadFromXml. The new body is created, loaded from the XML element, initialized, and added to the collision detection and scene graph.

Definition at line 868 of file world.cpp.

Robot * World::importRobot ( QString  filename  ) 

Creates a robot, loads it from a file and adds it to the world.

Loads a robot from a file and adds it to the world. filename must contain the full path to the robot. The file is expected to be in XML format. This function will open the file and read the robot file so that it initializes an instance of the correct class. It will then pass the XML root of the robot structure to the robot who will load its own information from the file.

Definition at line 924 of file world.cpp.

bool World::isSelected ( WorldElement e  )  const

Returns whether the world element pointed to by e is currently selected or not.

Checks whether an element is currently selected by looking in the selectedElementList

Definition at line 1197 of file world.cpp.

int World::load ( const QString &  filename  ) 

Loads the saved world from the file in filename.

Loads a simulation world file. These usually consists of one or more robots, graspable bodies and obstacles, each with its own transform. Optionally, a camera position might also be specified. Also restores any connections between robots.

Definition at line 479 of file world.cpp.

int World::loadFromXml ( const TiXmlElement root,
QString  rootPath 
)

Loads the saved world from the XML file in filename.

Definition at line 504 of file world.cpp.

DynamicBody * World::makeBodyDynamic ( Body b,
double  mass 
)

Creates a new dynamic body from the data in the body pointed to by b.

Makes a static element into a dynamic body by creating a DynamicBody from it and initializing default dynamic properties. The geometry is not loaded again, but it is added to the collision detection again.

Definition at line 1098 of file world.cpp.

double World::moveDynamicBodies ( double  timeStep  ) 

Moves all dynamic bodies based on their velocity and the length of the current timestep.

One of the two main functions of the dynamics time step. This function is called to move the bodies according to the velocities and accelerations found in the previous step. The move is attempted for the duration of the time step given in timeStep.

After all the bodies are moved, then collisions are checked. If any collisions are found, the move is traced back and the value of the times step is interpolated until the exact moment of contact is found. The actual value of the time step until contact is made is returned. If interpolation fails, a negative actual time step is returned. All the resulting contacts are added to the bodies that are in contact to be used for subsequent computations.

The same procedure is carried out if, by executing a full time step, a joint ends up outside of its legal range.

Definition at line 1793 of file world.cpp.

bool World::noCollision ( WorldElement e = NULL  ) 

Answers true if there are no collisions in the world, potentially involving a specified element.

Returns true if the element e is not colliding with anything else. Attempts to do it fast by returning as soon as any collision is found, and only looking at potential collisions that involve e.

Definition at line 1377 of file world.cpp.

void World::numElementsChanged (  )  [signal]

Signal that the number of world elements has changed.

Definition at line 121 of file moc_world.cpp.

vec3 World::pointDistanceToBody ( position  p,
Body b,
vec3 normal = NULL 
)

Computes the distance between a point and a body.

Returns a vector that is the shortest distance from the point p to the body b. If normal is not NULL, it is set to the surface normal of body b at the point closest to p. Everything is expressed in world coordinates.

Definition at line 1438 of file world.cpp.

void World::popDynamicState (  ) 

Restores the most recent dynamic state of each dynamic body by popping the state of each body's local stack.

Restores the dynamic state currently at the top of the stack

Definition at line 1763 of file world.cpp.

void World::pushDynamicState (  ) 

Calls upon each dynamic body to save its current dynamic state to the top of its stack of states.

Saves the current dynamic state (velocities and accelerations of all bodies) onto a stack.

Definition at line 1754 of file world.cpp.

bool World::queryTendonSelected (  )  [inline]

query whether a tendon is selected or not

Definition at line 278 of file world.h.

void World::readSettings (  )  [protected]

Reads the user preferences for the world settings. Under.

Reads in previously saved coefficients and parameters, if they exist. In Windows, they are read from the registry, in Linux they should be read from a file. It seems that currently only the Window implementation is here. If they don't exist, the default values are used.

Definition at line 311 of file world.cpp.

void World::removeElementFromSceneGraph ( WorldElement e  ) 

Removes from the scene graph an element that is already part of this world.

Remove an element that is part of this world from the Scene Graph; the element remains a part of the world and can be used in simulations; it is just not rendered anymore.

Definition at line 1081 of file world.cpp.

void World::removeRobot ( Robot robot  ) 

Removes the robot pointed to by robot from the world, then deletes it.

Removes a robot from the world and also deletes it.

Definition at line 1021 of file world.cpp.

void World::resetDynamics (  ) 

Resets dynamic simulation. Clears the dynamic stack, fixes all robot bases.

Resets the velocities and accelerations of all bodies; fixes the base robot of every collection of robots so that it is not affected by gravity and sets the desired pose of each robot to be it's current state so that the controllers try to maintain the current positions until the user requests something different.

Definition at line 1719 of file world.cpp.

void World::resetDynamicWrenches (  ) 

Resets the external wrench accumulator for all the dynamic bodies.

Definition at line 2130 of file world.cpp.

bool World::robotCollisionsAreOff ( Robot r,
WorldElement e 
)

Checks if collision between an entire robot and another element are on.

Definition at line 1229 of file world.cpp.

int World::save ( const QString &  filename  ) 

Save the current state of the world to a file.

Saves this world to a file. This includes all the world elements as well as positions in the world, and the positions and orientation of the camera. It does not save the dynamic state of the bodies.

Definition at line 749 of file world.cpp.

void World::saveSettings (  )  [protected]

Saves the user preferences for the world settings.

Saves current global settings to the registry

Definition at line 381 of file world.cpp.

void World::selectElement ( WorldElement e  ) 

Adds the worldElement pointed to by e to the list of selected elements.

Selects a world element. If the element is a Robot, also selects all of its links, plus the base. If it is a Body, it is also added to the list of selectedBodies.

Definition at line 1113 of file world.cpp.

void World::selectionsChanged (  )  [signal]

Signal that selections have changed.

Definition at line 115 of file moc_world.cpp.

void World::selectTendon ( int  i  ) 

Sets the selected tendon, receives an index into the selected hand's list of tendons.

Definition at line 2187 of file world.cpp.

void World::selectTendon ( Tendon t  ) 

Set selected tendon.

Definition at line 2171 of file world.cpp.

void World::setCurrentHand ( Hand hand  )  [inline]

Called when the user selects a new hand from the drop down menu.

Definition at line 365 of file world.h.

void World::setDefaults (  ) 

Sets all world settings to their original default values.

Returns the material name of a material with id matIdx int World::getMaterialName(int matIdx, QString &matName) const { if(i<0||i>=numMaterials) return FAILURE; matName = materialNames[i]; return SUCCESS; }

Sets all the default (hard-coded) coefficients and parameters. If the user later changes them, they are saved when the world is destroyed, and automatically loaded later, when the application is started again.

Definition at line 213 of file world.cpp.

void World::setModified (  )  [inline]

Sets the world modified flag. Should be done when a change has since the last save.

Definition at line 341 of file world.h.

bool World::softContactsAreOn (  )  [inline]

Returns whether soft contacts are on.

Definition at line 335 of file world.h.

void World::stepDynamics (  ) 

One complete step of the dynamics simulation.

A complete dynamics step:

  • moveDynamicBodies moves the bodies according to velocities computed at the previous time step.
  • active and passive joint forces are applied; contacts are detected
  • computeNewVelocities computes the velocities according to contact and joint constraints, for the next time step.

Definition at line 2149 of file world.cpp.

void World::tendonChange (  )  [inline]

signals that a tendon has changed status, we need to update the tendon status bar

Definition at line 290 of file world.h.

void World::tendonDetailsChanged (  )  [signal]

Signal that the selected tendon's status has changed.

Definition at line 151 of file moc_world.cpp.

void World::tendonSelectionChanged (  )  [signal]

Signal that a tendon has been (de)selected.

Definition at line 145 of file moc_world.cpp.

void World::toggleAllCollisions ( bool  on  ) 

Turns the collision detection system on or off.

Toggles all collisions. If on is false, all collisions in the world are disabled. If on is true, they are re-enabled.

Definition at line 1209 of file world.cpp.

void World::toggleCollisions ( bool  on,
WorldElement e1,
WorldElement e2 = NULL 
)

Toggle collisions for a world element (robot or body).

If e2 is NULL, is toggles collisions for e1 in general. Otherwise, it toggles collisions between e1 and e2. Remember that toggling collisions for a robot means applying the change to all of its links and the base

Definition at line 1314 of file world.cpp.

void World::turnOffDynamics (  ) 

Stops the dynamic simulation process.

Pauses dynamic simulation; no more time steps are computed

Definition at line 1697 of file world.cpp.

void World::turnOnDynamics (  ) 

Starts the dynamic simulation for this world.

Starts dynamic simulation. This is all the user has to do; from now on, dynamic steps are triggered automatically by an idle sensor. The only way to determine the motion of the bodies is to set desired values for the robot dofs and let the world time step computations and the robot dof controllers do the rest.

Use the resetDynamics routine to fix the base robot of every collection of robots so that it does not fall under gravity and to set the desired pose of each robot to be it's current state so that the controllers try to maintain the current positions until the user requests something different.

Definition at line 1685 of file world.cpp.

void World::updateGrasps (  ) 

Updates the grasp for any hand that has had contacts change since its grasp was last updated.

Asks each grasp to update itself (i.e. recompute its wrench spaces), presumably due to some change in contact geometry.

Definition at line 1555 of file world.cpp.

bool World::wasModified (  )  const [inline]

Returns whether this world has been modified since the last save.

Definition at line 305 of file world.h.


Friends And Related Function Documentation

friend class Body [friend]

Definition at line 193 of file world.h.

friend class DynamicBody [friend]

Definition at line 194 of file world.h.

friend class MainWindow [friend]

Definition at line 195 of file world.h.


Member Data Documentation

bool World::allCollisionsOFF [protected]

A flag to determine if collions checking is on or off.

Definition at line 152 of file world.h.

std::vector<Body *> World::bodyVec [protected]

A vector of pointers to ALL of the bodies in the world.

Definition at line 98 of file world.h.

double** World::cofTable [protected]

A numMaterials x numMaterials array of static coefficient of friction values.

Definition at line 170 of file world.h.

Hand* World::currentHand [protected]

Keeps track of which hand is currently the focus of menu commands.

Definition at line 137 of file world.h.

bool World::dynamicsOn [protected]

A flag to determine whether dynamics is currently being used or not.

Definition at line 176 of file world.h.

double World::dynamicsTimeStep [protected]

The length of the default dynamics time step.

Definition at line 182 of file world.h.

std::vector<GraspableBody *> World::GBVec [protected]

A vector of pointers to the graspable bodies in the world.

Definition at line 101 of file world.h.

std::vector<Hand *> World::handVec [protected]

A vector of pointers to the hands defined within this world.

Definition at line 107 of file world.h.

SoIdleSensor* World::idleSensor [protected]

A pointer to the Inventor idle sensor that is used when dynamics is on.

Definition at line 179 of file world.h.

bool World::isTendonSelected [protected]

keeps track is a tendon is selected or not

Definition at line 146 of file world.h.

SoSeparator* World::IVRoot [protected]

A pointer to the root of the world's Inventor scene graph.

Definition at line 161 of file world.h.

double** World::kcofTable [protected]

A numMaterials x numMaterials array of kinetic coefficient of friction values.

Definition at line 173 of file world.h.

std::vector<QString> World::materialNames [protected]

A vector of strings, one for each material name.

Definition at line 167 of file world.h.

A pointer to the collision detection instance.

Definition at line 158 of file world.h.

bool World::modified [protected]

Keeps track of whether the world has been modified since the last save.

Definition at line 134 of file world.h.

IVmgr* World::myIVmgr [protected]

Pointer to the IVmgr who controls the simulation.

Definition at line 88 of file world.h.

int World::numBodies [protected]

The number of bodies currently in this world.

Definition at line 110 of file world.h.

int World::numGB [protected]

The number of graspable bodies currently in this world.

Definition at line 113 of file world.h.

int World::numHands [protected]

The number of hands currently in this world.

Definition at line 119 of file world.h.

int World::numMaterials [protected]

The number of materials defined within this world.

Definition at line 164 of file world.h.

int World::numRobots [protected]

The number of robots currently in this world.

Definition at line 116 of file world.h.

int World::numSelectedBodies [protected]

The number of currently selected bodies.

Definition at line 131 of file world.h.

The number of currently selected body elements.

Definition at line 125 of file world.h.

int World::numSelectedElements [protected]

The number of currently selected elements.

Definition at line 122 of file world.h.

The number of currently selected body elements.

Definition at line 128 of file world.h.

std::vector<Robot *> World::robotVec [protected]

A vector of pointers to the robots defined within this world.

Definition at line 104 of file world.h.

std::vector<Body *> World::selectedBodyVec [protected]

A vector of pointers to the currently selected bodies.

Definition at line 143 of file world.h.

std::list<WorldElement *> World::selectedElementList [protected]

A list of pointers to the currently selected worldElements.

Definition at line 140 of file world.h.

pointer to selected tendon

Definition at line 149 of file world.h.

bool World::softContactsON [protected]

Turns on or off soft contacts, needs a switch in the Iv environment.

Definition at line 155 of file world.h.

double World::worldTime [protected]

Keeps track of the current simulation time.

Definition at line 95 of file world.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


graspit
Author(s):
autogenerated on Wed Jan 25 11:00:27 2012