The simulation world holds the world elements and handles their static and dynamic interactions. More...
#include <world.h>
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. | |
Body * | getBody (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. | |
CollisionInterface * | getCollisionInterface () |
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. | |
Hand * | getCurrentHand () 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. | |
GraspableBody * | getGB (int i) const |
Returns a pointer to the i-th graspable body defined in this world. | |
Hand * | getHand (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. | |
Robot * | getRobot (int i) const |
Returns a pointer to the i-th robot defined in this world. | |
Body * | getSelectedBody (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 | |
Tendon * | getSelectedTendon () |
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. | |
Body * | importBody (QString bodyType, QString filename) |
Creates a new body of type bodyType, then calls the load routine of that body. | |
Body * | importBodyFromXml (QString bodyType, const TiXmlElement *child, QString rootPath) |
Creates a new body of type bodyType, then calls the loadFromXml routine of that body. | |
Robot * | importRobot (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. | |
DynamicBody * | makeBodyDynamic (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. | |
Hand * | currentHand |
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. | |
CollisionInterface * | mCollisionInterface |
A pointer to the collision detection instance. | |
bool | modified |
Keeps track of whether the world has been modified since the last save. | |
IVmgr * | myIVmgr |
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. | |
Tendon * | selectedTendon |
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 |
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.
World::World | ( | QObject * | parent = 0 , |
|
const char * | name = 0 , |
|||
IVmgr * | mgr = NULL | |||
) |
World::~World | ( | ) |
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.
void World::addElementToSceneGraph | ( | WorldElement * | e | ) |
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.
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.
bool World::collisionsAreOff | ( | WorldElement * | e1 = NULL , |
|
WorldElement * | e2 = NULL | |||
) |
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.
void World::deselectAll | ( | ) |
void World::deselectElement | ( | WorldElement * | e | ) |
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.
bool World::dynamicsAreOn | ( | ) | const [inline] |
void World::dynamicsCB | ( | void * | data, | |
SoSensor * | sensor | |||
) | [static, protected] |
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] |
void World::findAllContacts | ( | ) |
void World::findContacts | ( | Body * | b | ) |
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.
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.
ContactData World::findVirtualContact | ( | Link * | link, | |
Body * | object | |||
) |
Body* World::getBody | ( | int | i | ) | const [inline] |
void World::getBvs | ( | Body * | b, | |
int | depth, | |||
std::vector< BoundingBox > * | bvs | |||
) |
double World::getCOF | ( | int | mat1, | |
int | mat2 | |||
) | [inline] |
CollisionInterface* World::getCollisionInterface | ( | ) | [inline] |
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.
Hand* World::getCurrentHand | ( | ) | const [inline] |
int World::getCurrentHandNumberTendons | ( | ) |
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
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.
GraspableBody* World::getGB | ( | int | i | ) | const [inline] |
Hand* World::getHand | ( | int | i | ) | const [inline] |
SoSeparator* World::getIVRoot | ( | ) | const [inline] |
double World::getKCOF | ( | int | mat1, | |
int | mat2 | |||
) | [inline] |
int World::getMaterialIdx | ( | const QString & | matName | ) | const |
QString World::getMaterialName | ( | int | i | ) | const [inline] |
int World::getNumBodies | ( | ) | const [inline] |
int World::getNumGB | ( | ) | const [inline] |
int World::getNumHands | ( | ) | const [inline] |
int World::getNumMaterials | ( | ) | const [inline] |
int World::getNumRobots | ( | ) | const [inline] |
int World::getNumSelectedBodies | ( | ) | const [inline] |
int World::getNumSelectedBodyElements | ( | ) | const [inline] |
int World::getNumSelectedElements | ( | ) | const [inline] |
int World::getNumSelectedRobotElements | ( | ) | const [inline] |
Robot* World::getRobot | ( | int | i | ) | const [inline] |
Body* World::getSelectedBody | ( | int | i | ) | const [inline] |
const std::list<WorldElement *>& World::getSelectedElementList | ( | ) | const [inline] |
QString World::getSelectedHandTendonName | ( | int | i | ) |
Tendon* World::getSelectedTendon | ( | ) | [inline] |
double World::getTimeStep | ( | ) | const [inline] |
double World::getWorldTime | ( | ) | const [inline] |
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.
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.
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.
bool World::isSelected | ( | WorldElement * | e | ) | const |
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.
int World::loadFromXml | ( | const TiXmlElement * | root, | |
QString | rootPath | |||
) |
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.
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.
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.
void World::numElementsChanged | ( | ) | [signal] |
Signal that the number of world elements has changed.
Definition at line 121 of file moc_world.cpp.
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.
void World::popDynamicState | ( | ) |
void World::pushDynamicState | ( | ) |
bool World::queryTendonSelected | ( | ) | [inline] |
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.
void World::removeElementFromSceneGraph | ( | WorldElement * | e | ) |
void World::removeRobot | ( | Robot * | robot | ) |
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.
void World::resetDynamicWrenches | ( | ) |
bool World::robotCollisionsAreOff | ( | Robot * | r, | |
WorldElement * | e | |||
) |
int World::save | ( | const QString & | filename | ) |
void World::saveSettings | ( | ) | [protected] |
void World::selectElement | ( | WorldElement * | e | ) |
void World::selectionsChanged | ( | ) | [signal] |
Signal that selections have changed.
Definition at line 115 of file moc_world.cpp.
void World::selectTendon | ( | int | i | ) |
void World::selectTendon | ( | Tendon * | t | ) |
void World::setCurrentHand | ( | Hand * | hand | ) | [inline] |
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.
void World::setModified | ( | ) | [inline] |
bool World::softContactsAreOn | ( | ) | [inline] |
void World::stepDynamics | ( | ) |
One complete step of the dynamics simulation.
A complete dynamics step:
void World::tendonChange | ( | ) | [inline] |
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 | ) |
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
void World::turnOffDynamics | ( | ) |
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.
void World::updateGrasps | ( | ) |
bool World::wasModified | ( | ) | const [inline] |
friend class DynamicBody [friend] |
friend class MainWindow [friend] |
bool World::allCollisionsOFF [protected] |
std::vector<Body *> World::bodyVec [protected] |
double** World::cofTable [protected] |
Hand* World::currentHand [protected] |
bool World::dynamicsOn [protected] |
double World::dynamicsTimeStep [protected] |
std::vector<GraspableBody *> World::GBVec [protected] |
std::vector<Hand *> World::handVec [protected] |
SoIdleSensor* World::idleSensor [protected] |
bool World::isTendonSelected [protected] |
SoSeparator* World::IVRoot [protected] |
double** World::kcofTable [protected] |
std::vector<QString> World::materialNames [protected] |
CollisionInterface* World::mCollisionInterface [protected] |
bool World::modified [protected] |
IVmgr* World::myIVmgr [protected] |
int World::numBodies [protected] |
int World::numGB [protected] |
int World::numHands [protected] |
int World::numMaterials [protected] |
int World::numRobots [protected] |
int World::numSelectedBodies [protected] |
int World::numSelectedBodyElements [protected] |
int World::numSelectedElements [protected] |
int World::numSelectedRobotElements [protected] |
std::vector<Robot *> World::robotVec [protected] |
std::vector<Body *> World::selectedBodyVec [protected] |
std::list<WorldElement *> World::selectedElementList [protected] |
Tendon* World::selectedTendon [protected] |
bool World::softContactsON [protected] |
double World::worldTime [protected] |