A generic simulation body. More...
#include <body.h>
Public Member Functions | |
virtual void | addContact (Contact *c) |
Adds a contact to this body. | |
void | addIVMat (bool clone=false) |
Adds additional material nodes so we can control the transparency of the body. | |
virtual void | addToIvc (bool ExpectEmpty=false) |
Adds this body to the collision detection system. | |
virtual void | addVirtualContact (Contact *c) |
Adds a virtual contact to this body. | |
Body (World *w, const char *name=0) | |
Empty body with invalid material and no geometry. | |
virtual void | breakContacts () |
Removes all the cotacts on this body (usually after a move). | |
virtual void | breakVirtualContacts () |
Removes all virtual contacts on this body. | |
Contact * | checkContactInheritance (Contact *c) |
Checks if a current contact is the same as a contact from the previous time step. | |
virtual void | cloneFrom (const Body *original) |
Make this body a clone of another body. | |
virtual void | cloneToIvc (const Body *original) |
Adds this body to the collision detection system as a clone of another body. | |
virtual bool | contactsPreventMotion (const transf &motion) const |
Returns true if current contacts prevent motion in the given direction. | |
int | convert2xml (QString filename) |
Convert the body information to xml and link the xml to the given geometry file. | |
bool | frictionConesShown () const |
int | getBirdNumber () |
Which bird in the flock controlls this body. | |
std::list< Contact * > | getContacts (Body *b=NULL) const |
FlockTransf * | getFlockTran () |
Where on the body the Flock of Birds sensor is mounted. | |
void | getGeometryTriangles (std::vector< Triangle > *triangles) const |
void | getGeometryVertices (std::vector< position > *vertices) const |
SoSeparator * | getIVContactIndicators () const |
SoSeparator * | getIVGeomRoot () const |
SoMaterial * | getIVMat () const |
SoTransform * | getIVTran () const |
int | getMaterial () const |
int | getNumContacts (Body *b=NULL) const |
int | getNumVirtualContacts () const |
virtual WorldElement * | getOwner () |
Individual bodies belong to themselves. Links override this and return their robot. | |
bool | getRenderGeometry () const |
Gets the current rendering requests state. | |
transf const & | getTran () const |
float | getTransparency () const |
Returns the transparency of this body for rendering. | |
std::list< Contact * > | getVirtualContacts () const |
double | getYoungs () |
Returns the Young's modulus for this body. | |
virtual bool | isDynamic () const |
Determines whether instance is dynamic (overridden in DynamicBody). | |
bool | isElastic () |
Returns whether this body is soft (elastic) or not. Affect contact models. | |
virtual int | load (const QString &filename) |
Load the body information from a file. | |
virtual int | loadContactData (QString fn) |
Load in virtual contacts specified in file fn. | |
virtual int | loadFromXml (const TiXmlElement *root, QString rootPath) |
Loads the body information from an XML structure. | |
int | loadGeometryIV (const QString &filename) |
Loads the geometry of the body from an Inventor file that can be read by Coin (IV or VRML). | |
int | loadGeometryMemory (const std::vector< position > &vertices, const std::vector< int > &triangles) |
Loads the geometry from a vector of vertices and one of triangles. | |
int | loadGeometryOFF (const QString &filename) |
Loads the geometry of the body from an .off file. | |
int | loadGeometryPLY (const QString &filename) |
Loads the geometry of the body from a .ply file. | |
virtual void | redrawFrictionCones () |
Asks all contacts to recompute their friction cones. | |
virtual void | removeContact (Contact *c) |
Removed a contact from this body. | |
virtual void | removePrevContact (Contact *c) |
Removes a contact from the list of contacts at the previous time step. | |
virtual void | resetContactList () |
Moves all current contacts to the list of previous contacts. | |
virtual int | saveToXml (QTextStream &xml) |
Saves the body information to an XML structure. | |
void | setBVGeometry (const std::vector< BoundingBox > &bvs) |
virtual void | setDefaultViewingParameters () |
Default parameters for transparency, show friction cones, etc. | |
void | setMaterial (int mat) |
Sets the material of this body. | |
void | setRenderGeometry (bool s) |
Enables / disabled automatic render requests when this body is moved. | |
virtual int | setTran (transf const &newTr) |
Sets the body to another location in the world. Collisions are not checked. | |
void | setTransparency (float t) |
Sets the transparency of this body for rendering. | |
void | showFrictionCones (bool on, int vc=0) |
Shows or hides the friction cones for this body. | |
bool | usesFlock () |
Tells us if this body's position is controlled by the Flock of Birds. | |
virtual | ~Body () |
Breaks all contacts; does not remove body from collision detection or scene graph. | |
Static Public Attributes | |
static const float | CONE_HEIGHT = 20.0 |
Parameter to control the height of friction cones. | |
Protected Member Functions | |
Body (const Body &b) | |
Copy constructor. | |
void | createAxesGeometry () |
Creates the axes for display. | |
virtual void | getBodyList (std::vector< Body * > *bodies) |
Adds itself to the given vector of Bodies. | |
void | initializeIV () |
Initialize an empty scene graph structure with just the needed roots. | |
Protected Attributes | |
SoScale * | axesScale |
Inventor scale for axes so that they extend outside the body. | |
SoTranslation * | axesTranToCOG |
Inventor transform from body frame to center of gravity. | |
std::list< Contact * > | contactList |
The current contacts on the body. | |
SoSwitch * | IVAxes |
Inventor root of the axes in the body subtree. | |
SoSeparator * | IVBVRoot |
A pointer to a node that can hold the geometry of the bounding volume struture. | |
SoSeparator * | IVContactIndicators |
A pointer to the root of the friction cones on this body. | |
SoSeparator * | IVGeomRoot |
A pointer to the root node of the geometry of this model. | |
SoMaterial * | IVMat |
A pointer to the material node that controls this body's transparency. | |
SoTransform * | IVTran |
A pointer to the Inventor transform for the body. | |
SoSeparator * | IVWorstCase |
Inventor root of the worst case disturbance wrench indicator. | |
int | material |
The surface material of the body specified as an index to the world material list. | |
int | mBirdNumber |
This tells us which bird in the flock the object is using. | |
FlockTransf | mFlockTran |
The relative tranform used for the Flock of Birds. | |
QString | mGeometryFilename |
The file that geometry was loaded from, if any. | |
QString | mGeometryFileType |
Type of geometry file, for now either "Inventor" or "off". | |
bool | mIsElastic |
Tells us whether this is a rigid body or not (affects friction models). | |
bool | mRenderGeometry |
When this is un-checked, changing the transform of this body will not trigger a redraw. | |
bool | mUsesFlock |
This flag tells us if this body follows the Flock of Birds tracker. | |
int | numContacts |
The number of contacts on the body. | |
std::list< Contact * > | prevContactList |
The contacts on the body at the previous time step. | |
bool | showFC |
This flag determines whether the body's friction cones should be shown. | |
bool | showVC |
This flag determines whether the body's virtual contacts should be shown. | |
transf | Tran |
The body's world position (translations are in mm). | |
std::list< Contact * > | virtualContactList |
Virtual Contacts on this body. See the Virtual Contact class for explanation. | |
double | youngMod |
The Young's Modulus of the material, it describes its elasticity. | |
Friends | |
QTextStream & | operator<< (QTextStream &os, const Body &b) |
Prints the name and material of this body to a stream. |
A generic simulation body.
A generic body is defined by its geometry, its material, and a transform. Body instances are considered obstacles--they can form contacts with other objects but are not part of of the dynamics system.
Definition at line 76 of file body.h.
Body::Body | ( | const Body & | b | ) | [protected] |
Body::Body | ( | World * | w, | |
const char * | name = 0 | |||
) |
Body::~Body | ( | ) | [virtual] |
Breaks all contacts; does not remove body from collision detection or scene graph.
Breaks all contacts; it is up to the world to also remove it from the collision detection system or the scene graph. In general, do not delete bodies directly, but use World::removeElement(...)instead which can also delete them.
void Body::addContact | ( | Contact * | c | ) | [virtual] |
Adds a contact to this body.
Adds contact c to the body's contact list. Assumes the contact is not already in the list.
void Body::addIVMat | ( | bool | clone = false |
) |
Adds additional material nodes so we can control the transparency of the body.
After the geometry has been set, this function adds a new Material node after any Material node already present so we can change the transparency of this object. Does not work on bodies loaded from VRML files, as they have different types of material nodes. I have tried also searching for SoVRMLMaterial nodes, but the search fails even if those nodes exist; I suppose that is a bug in Coin.
void Body::addToIvc | ( | bool | ExpectEmpty = false |
) | [virtual] |
void Body::addVirtualContact | ( | Contact * | c | ) | [virtual] |
void Body::breakContacts | ( | ) | [virtual] |
void Body::breakVirtualContacts | ( | ) | [virtual] |
Checks if a current contact is the same as a contact from the previous time step.
Checks if this contact inherits some other contact from the prevContactList. The check looks of contact points are close, normals agree and the second body is the same. If inheritance is found, some properites of the contact are passed from the previous contact to this one.
void Body::cloneFrom | ( | const Body * | original | ) | [virtual] |
Make this body a clone of another body.
Clones this body from an original. This means that the two bodies have independent transform, materials, properties, etc, BUT they share the scene graph geometry and the collision detection geometry. They can still be used for collision detection independently as they can have different transforms.
WARNING: cloning mechanism is incomplete. If the original is deleted, the clone becomes unpredicateble and can cause the system to crash
void Body::cloneToIvc | ( | const Body * | original | ) | [virtual] |
bool Body::contactsPreventMotion | ( | const transf & | motion | ) | const [virtual] |
Returns true if current contacts prevent motion in the given direction.
Given a motion relative to body coordinates, this determines whether the current contacts allow that motion.
Implements WorldElement.
int Body::convert2xml | ( | QString | filename | ) |
Convert the body information to xml and link the xml to the given geometry file.
void Body::createAxesGeometry | ( | ) | [protected] |
bool Body::frictionConesShown | ( | ) | const [inline] |
int Body::getBirdNumber | ( | ) | [inline] |
virtual void Body::getBodyList | ( | std::vector< Body * > * | bodies | ) | [inline, protected, virtual] |
Adds itself to the given vector of Bodies.
Implements WorldElement.
FlockTransf* Body::getFlockTran | ( | ) | [inline] |
void Body::getGeometryTriangles | ( | std::vector< Triangle > * | triangles | ) | const |
void Body::getGeometryVertices | ( | std::vector< position > * | vertices | ) | const |
SoSeparator* Body::getIVContactIndicators | ( | ) | const [inline] |
SoSeparator* Body::getIVGeomRoot | ( | ) | const [inline] |
SoMaterial* Body::getIVMat | ( | ) | const [inline] |
SoTransform* Body::getIVTran | ( | ) | const [inline] |
int Body::getMaterial | ( | ) | const [inline] |
Returns the current material of the body.
int Body::getNumContacts | ( | Body * | b = NULL |
) | const |
int Body::getNumVirtualContacts | ( | ) | const [inline] |
virtual WorldElement* Body::getOwner | ( | ) | [inline, virtual] |
bool Body::getRenderGeometry | ( | ) | const [inline] |
transf const& Body::getTran | ( | ) | const [inline, virtual] |
Returns the current pose of the body.
Implements WorldElement.
float Body::getTransparency | ( | ) | const |
Returns the transparency of this body for rendering.
Returns the current transparency value for the body (between 0 and 1).
std::list<Contact *> Body::getVirtualContacts | ( | ) | const [inline] |
double Body::getYoungs | ( | ) | [inline] |
void Body::initializeIV | ( | ) | [protected] |
virtual bool Body::isDynamic | ( | ) | const [inline, virtual] |
Determines whether instance is dynamic (overridden in DynamicBody).
Reimplemented in DynamicBody.
bool Body::isElastic | ( | ) | [inline] |
int Body::load | ( | const QString & | filename | ) | [virtual] |
Load the body information from a file.
Opens and loads a body information file. filename is the complete path to the body file, which should be in XML format (with a .xml extension) and can contain a number of Graspit-specific properties as XML tags, as well as a pointer to a different file which contains the geometry itself.
Alternatively, filename can also point directly to the geometry file.The type of the file will be detected by its extension (.iv, .wrl, .off or .ply) in which case GraspIt will use the default values for all the properties that normally come from the XML tags.
int Body::loadContactData | ( | QString | fn | ) | [virtual] |
int Body::loadFromXml | ( | const TiXmlElement * | root, | |
QString | rootPath | |||
) | [virtual] |
Loads the body information from an XML structure.
Parses the root node of an XML structure containing information for a body. It looks for all the relevant properties. Some of the properties are optional and if they are not found, they will be set to default values. Others will cause a failure if they are not present.
Reimplemented in DynamicBody.
int Body::loadGeometryIV | ( | const QString & | filename | ) |
Loads the geometry of the body from an Inventor file that can be read by Coin (IV or VRML).
Loads only the geometry part of this object, without any other GraspIt specific information such as mass, material etc. The file must be in a format that is readable by Coin, which for now means either Inventor (.iv) or VRML.
int Body::loadGeometryMemory | ( | const std::vector< position > & | vertices, | |
const std::vector< int > & | triangles | |||
) |
int Body::loadGeometryOFF | ( | const QString & | filename | ) |
int Body::loadGeometryPLY | ( | const QString & | filename | ) |
Loads the geometry of the body from a .ply file.
Loads the geometry of this body from a .ply file. Uses ply loading code from ROS by Willow Garage, which in turn uses code from Greg Turk, Georgia Institute of Technology. PLY loading seems to be fairly complex, as the ply format is very extensible. Right now, this will only load vertices and triangles and nothing else, not even other types of faces. Could be extended in the future.
void Body::redrawFrictionCones | ( | ) | [virtual] |
void Body::removeContact | ( | Contact * | c | ) | [virtual] |
Removed a contact from this body.
Removes contact c from the body's contact list. Assumes the contact is in the list.
void Body::removePrevContact | ( | Contact * | c | ) | [virtual] |
void Body::resetContactList | ( | ) | [virtual] |
int Body::saveToXml | ( | QTextStream & | xml | ) | [virtual] |
Saves the body information to an XML structure.
Reimplemented in DynamicBody.
void Body::setBVGeometry | ( | const std::vector< BoundingBox > & | bvs | ) |
void Body::setDefaultViewingParameters | ( | ) | [virtual] |
Default parameters for transparency, show friction cones, etc.
Reimplemented in DynamicBody, and GraspableBody.
void Body::setMaterial | ( | int | mat | ) |
void Body::setRenderGeometry | ( | bool | s | ) |
int Body::setTran | ( | transf const & | tr | ) | [virtual] |
Sets the body to another location in the world. Collisions are not checked.
Sets the current world pose of the body to tr. Collisions are not checked.
Implements WorldElement.
Reimplemented in DynamicBody.
void Body::setTransparency | ( | float | t | ) |
Sets the transparency of this body for rendering.
Set the current transparency value for the body. t is a value between 0 and 1, where 0 is opaque, 1 is transparent.
void Body::showFrictionCones | ( | bool | on, | |
int | vc = 0 | |||
) |
bool Body::usesFlock | ( | ) | [inline] |
QTextStream& operator<< | ( | QTextStream & | os, | |
const Body & | b | |||
) | [friend] |
SoScale* Body::axesScale [protected] |
SoTranslation* Body::axesTranToCOG [protected] |
const float Body::CONE_HEIGHT = 20.0 [static] |
std::list<Contact *> Body::contactList [protected] |
SoSwitch* Body::IVAxes [protected] |
SoSeparator* Body::IVBVRoot [protected] |
SoSeparator* Body::IVContactIndicators [protected] |
SoSeparator* Body::IVGeomRoot [protected] |
SoMaterial* Body::IVMat [protected] |
SoTransform* Body::IVTran [protected] |
SoSeparator* Body::IVWorstCase [protected] |
int Body::material [protected] |
int Body::mBirdNumber [protected] |
FlockTransf Body::mFlockTran [protected] |
QString Body::mGeometryFilename [protected] |
QString Body::mGeometryFileType [protected] |
bool Body::mIsElastic [protected] |
bool Body::mRenderGeometry [protected] |
bool Body::mUsesFlock [protected] |
int Body::numContacts [protected] |
std::list<Contact *> Body::prevContactList [protected] |
bool Body::showFC [protected] |
bool Body::showVC [protected] |
transf Body::Tran [protected] |
std::list<Contact *> Body::virtualContactList [protected] |
double Body::youngMod [protected] |