Handles 3D interactions with the world. More...
#include <ivmgr.h>
Public Slots | |
void | drawDynamicForces () |
void | drawUnbalancedForces () |
void | drawWorstCaseWrenches () |
void | restoreCameraPos () |
void | saveCameraPos () |
void | saveNextImage () |
Public Member Functions | |
void | beginMainLoop () |
void | deselectBody (Body *b) |
void | emptyWorld () |
void | flipStereo () |
Not implemented. | |
void | getCamera (float &px, float &py, float &pz, float &q1, float &q2, float &q3, float &q4, float &fd) |
Gets the camera position, orientaion and focal distance. | |
transf | getCameraTransf () |
db_planner::DatabaseManager * | getDBMgr () |
Get the main database manager, when CGDB support is enabled. | |
SoSeparator * | getPointers () const |
StereoViewer * | getViewer () const |
World * | getWorld () const |
void | hilightObjContact (int contactNum) |
IVmgr (QWidget *parent=0, const char *name=0, Qt::WFlags f=0) | |
int | saveCameraPositions (const char *filename) |
void | saveImage (QString filename) |
void | saveImageSequence (const char *fileStr) |
void | setCamera (double px, double py, double pz, double q1, double q2, double q3, double q4, double fd) |
Sets the camera position, orientaion and focal distance. | |
void | setCameraTransf (transf tr) |
void | setDBMgr (db_planner::DatabaseManager *) |
Set the main database manager. Should only be called by the DB connection dialog. | |
void | setStereo (bool s) |
void | setStereoWindow (QWidget *parent) |
Not used right now. | |
void | setTool (ToolType newTool) |
void | unhilightObjContact (int contactNum) |
int | useSavedCameraPositions (const char *filename) |
~IVmgr () | |
Private Member Functions | |
void | deleteSelections () |
void | drawBodyWrench (GraspableBody *body, const double *wrench) |
Draws a wrench indicator on a body. | |
void | drawWireFrame (SoSeparator *elementRoot) |
void | handleDeselection (SoPath *p) |
void | handleSelection (SoPath *p) |
void | keyPressed (SoEventCallback *eventCB) |
void | makeCenterball (WorldElement *selectedElement, Body *surroundMe) |
void | makeHandleBox (WorldElement *selectedElement, Body *surroundMe) |
void | makeJointDraggers (Robot *robot, KinematicChain *chain) |
SoPath * | pickFilter (const SoPickedPoint *pick) |
void | prismaticJointChanged (DraggerInfo *dInfo) |
void | revoluteJointChanged (DraggerInfo *dInfo) |
void | revoluteJointClicked (DraggerInfo *dInfo) |
void | revoluteJointFinished (DraggerInfo *dInfo) |
void | setCtrlDown (SbBool status) |
void | setShiftDown (SbBool status) |
void | setupPointers () |
void | spaceBar () |
void | transRot (DraggerInfo *dInfo) |
Static Private Member Functions | |
static void | deselectionCB (void *, SoPath *p) |
static callback routine for deselections | |
static void | keyPressedCB (void *, SoEventCallback *eventCB) |
static callback routine for keyboard events | |
static SoPath * | pickFilterCB (void *, const SoPickedPoint *pick) |
static callback routine for pick events (before selections or deselections) | |
static void | prismaticJointChangedCB (void *dInfo, SoDragger *dragger) |
static callback routine for when an arrow dragger is moved | |
static void | revoluteJointChangedCB (void *dInfo, SoDragger *dragger) |
static callback routine for when a disc dragger is moved | |
static void | revoluteJointClickedCB (void *dInfo, SoDragger *dragger) |
static callback routine for when a disc dragger is clicked | |
static void | revoluteJointFinishedCB (void *dInfo, SoDragger *dragger) |
static callback routine for when a disc dragger is released | |
static void | selectionCB (void *, SoPath *p) |
static callback routine for selections | |
static void | shiftOrCtrlDownCB (void *, SoEventCallback *eventCB) |
static callback routine for mouse events | |
static void | transRotCB (void *dInfo, SoDragger *dragger) |
static callback routine for when a body dragger is moved | |
Private Attributes | |
FILE * | camerafp |
File pointer used to read or record camera positions when making a movie. | |
std::vector< SoBlinker * > | contactForceBlinkerVec |
An array of pointers to blinker nodes that correspond to individual contact force indicators. | |
SbBool | CtrlDown |
A flag indicating whether the control key is down during a mouse click. | |
ToolType | currTool |
Current interaction tool selected (translate, rotate, or select). | |
SoSeparator * | draggerRoot |
Pointer to the sub-tree of. | |
SoMaterial * | dynForceMat |
Pointer to the material node controlling the color of dynamic force indicatores. | |
int | imgSeqCounter |
Current frame counter used in recording an image sequence. | |
const char * | imgSeqStr |
Base filename fir recording an image sequence. | |
SoSeparator * | junk |
Pointer to an empty separator. | |
db_planner::DatabaseManager * | mDBMgr |
The main and only interface for the CGDB; all interaction with the CGDB should go through this. | |
StereoViewer * | myViewer |
A pointer to the examiner viewer which inventor component facilitating user interaction. | |
SoSeparator * | pointers |
Pointers to various structures used for visual feedback. | |
SoSeparator * | sceneRoot |
Pointer to the root of the entire Inventor scene graph. | |
SoSelection * | selectionRoot |
Pointer to the sub-tree of selectable Inventor objects. | |
SbBool | ShiftDown |
A flag indicating whether the shift key is down during a mouse click. | |
SoSeparator * | wireFrameRoot |
Pointer to sub-tree containing wireframe versions of bodies when they are selected. | |
World * | world |
Points to the main world associated with this iteraction manager. | |
Static Private Attributes | |
static IVmgr * | ivmgr = 0 |
Global ivmgr pointer for use with static callback routines. There is only one ivmgr. |
Handles 3D interactions with the world.
There is one instance of the Inventor Manager within the application. It handles all 3D user interaction with the main world. An examiner viewer provides the user with a way to manipulate a virtual camera to view the simulation world. The user can also use the mouse to select bodies, or create draggers that allow manipulation of elements within the world. This class also handles the display of contact forces and some other indicators, and can render and save an image of the current scene.
Definition at line 122 of file ivmgr.h.
IVmgr::IVmgr | ( | QWidget * | parent = 0 , |
|
const char * | name = 0 , |
|||
Qt::WFlags | f = 0 | |||
) |
Initializes the IVmgr instance. It creates a new World that is the main world that the user interacts with. It creates the examiner viewer that allows the user to navigate within the world and interact with it. It sets up the root of the entire Inventor scene graph tree as well as sub-nodes that handle callbacks for user selections and key presses. Sub-tree roots for draggers and wireframe models, which indicate when bodies are selected, are also created.
IVmgr::~IVmgr | ( | ) |
void IVmgr::deleteSelections | ( | ) | [private] |
If the select tool is currently being used and the user hits the delete key, then all currently selected bodies will be deleted. This routine does not allow links of robots to be deleted, because of the change it would require in the robot structure. Sometime in the future we'll deal with that. However, if the whole robot is selected, it will be deleted.
void IVmgr::deselectionCB | ( | void * | , | |
SoPath * | p | |||
) | [static, private] |
void IVmgr::drawBodyWrench | ( | GraspableBody * | body, | |
const double * | wrench | |||
) | [private] |
void IVmgr::drawDynamicForces | ( | ) | [slot] |
This routine adds arrows within each of the friction cones that indicate the size of the dynamic contact forces that were solved for. This still doesn't handle the display of any torsional forces at soft finger contacts. If dynamics are not on, blinker nodes are added so that when a contact force is selected from the list the associated contact force indicator will blink.
void IVmgr::drawUnbalancedForces | ( | ) | [slot] |
void IVmgr::drawWireFrame | ( | SoSeparator * | elementRoot | ) | [private] |
void IVmgr::drawWorstCaseWrenches | ( | ) | [slot] |
void IVmgr::emptyWorld | ( | ) |
void IVmgr::getCamera | ( | float & | px, | |
float & | py, | |||
float & | pz, | |||
float & | q1, | |||
float & | q2, | |||
float & | q3, | |||
float & | q4, | |||
float & | fd | |||
) |
db_planner::DatabaseManager* IVmgr::getDBMgr | ( | ) | [inline] |
SoSeparator* IVmgr::getPointers | ( | ) | const [inline] |
StereoViewer* IVmgr::getViewer | ( | ) | const [inline] |
World* IVmgr::getWorld | ( | ) | const [inline] |
void IVmgr::handleDeselection | ( | SoPath * | p | ) | [private] |
void IVmgr::handleSelection | ( | SoPath * | p | ) | [private] |
This callback routine is invoked whenever an Inventor selection occurs. When this routine is called because of a user click, the path sent to this routine is determined by the pickFilter. The action that occurs upon selection depends on the current tool selected. If a kinematic chain is selected, and the rotate or translate tool is selected, joint draggers are created. Otherwise, if the rotate tool is being used, then a centerball is created around the chosen body. If the translate tool is being used, then a handlebox is created around the chosen body. If the select tool is being used, the chosen body is selected within GraspIt! and a wireframe version of the body is drawn to indicate the selection.
void IVmgr::hilightObjContact | ( | int | contactNum | ) |
void IVmgr::keyPressed | ( | SoEventCallback * | eventCB | ) | [private] |
This callback routine is invoked when the user presses a key while the arrow (not the hand) viewer tool is selected. The space bar toggles the state of the dynamics. The delete key deletes currently selected bodies. The G key starts an autograps of the current hand.
void IVmgr::keyPressedCB | ( | void * | , | |
SoEventCallback * | eventCB | |||
) | [static, private] |
void IVmgr::makeCenterball | ( | WorldElement * | selectedElement, | |
Body * | surroundMe | |||
) | [private] |
Creates a centerball dragger for the provided worldElement around the body surroundMe, and sets up the value changed callback for the dragger. For a free body, the worldElement and surroundMe point to the same body. For a robot, the worldElement points to the robot and surround me points to the base link of the robot.
void IVmgr::makeHandleBox | ( | WorldElement * | selectedElement, | |
Body * | surroundMe | |||
) | [private] |
Creates a handlebox dragger for the provided worldElement around the body surroundMe, and sets up the value changed callback for the dragger. For a free body, the worldElement and surroundMe point to the same body. For a robot, the worldElement points to the robot and surround me points to the base link of the robot.
void IVmgr::makeJointDraggers | ( | Robot * | robot, | |
KinematicChain * | chain | |||
) | [private] |
Creates the joint draggers for each DOF in the provided kinematic chain, and sets up the value changed callback for each dragger. Only the first joint in the chain associated with a given DOF has a dragger connected to it. In other words, passive joints don't have draggers. The scale of the joint dragger is controlled by a parameter found in the joints section of the robot configuration file.
SoPath * IVmgr::pickFilter | ( | const SoPickedPoint * | pick | ) | [private] |
This callback routine is invoked when a user clicks within the scene and controls what Inventor body is picked. If a dragger is clicked, a empty path is returned because we don't want the dragger to be selected in the Inventor sense. If the translate or rotate tool is currently being used and a link of a kinematic chain is clicked, pick the whole chain. If the base of a robot is clicked, pick the whole robot. If the current tool is the select tool, and a link is clicked that has already been selected, pick the whole robot. Otherwise pick the body that was clicked.
SoPath * IVmgr::pickFilterCB | ( | void * | , | |
const SoPickedPoint * | pick | |||
) | [static, private] |
void IVmgr::prismaticJointChanged | ( | DraggerInfo * | dInfo | ) | [private] |
The callback routine is invoked whenever an arrow dragger controlling a prismatic DOF is moved by the user. It requires a pointer to the dragger's associated info structure. It prevents the user from moving the dragger past the minimum or maximum DOF limits. It calls the associated robot's moveDOFto routine to peform the move, and after it is completed or a contact prevents further motion it asks the world to update the grasps and sets the current translation of the arrow dragger.
void IVmgr::prismaticJointChangedCB | ( | void * | dInfo, | |
SoDragger * | dragger | |||
) | [static, private] |
void IVmgr::restoreCameraPos | ( | ) | [slot] |
void IVmgr::revoluteJointChanged | ( | DraggerInfo * | dInfo | ) | [private] |
The callback routine is invoked whenever a disc dragger controlling a revolute DOF is moved by the user. It requires a pointer to the dragger's associated info structure. It prevents the user from moving the dragger past the minimum or maximum DOF limits. It calls the associated robot's moveDOFto routine to peform the move, and after it is completed or a contact prevents further motion it asks the world to update the grasps and sets the current angle of the disc dragger.
void IVmgr::revoluteJointChangedCB | ( | void * | dInfo, | |
SoDragger * | dragger | |||
) | [static, private] |
void IVmgr::revoluteJointClicked | ( | DraggerInfo * | dInfo | ) | [private] |
void IVmgr::revoluteJointClickedCB | ( | void * | dInfo, | |
SoDragger * | dragger | |||
) | [static, private] |
void IVmgr::revoluteJointFinished | ( | DraggerInfo * | dInfo | ) | [private] |
void IVmgr::revoluteJointFinishedCB | ( | void * | dInfo, | |
SoDragger * | dragger | |||
) | [static, private] |
void IVmgr::saveCameraPos | ( | ) | [slot] |
int IVmgr::saveCameraPositions | ( | const char * | filename | ) |
Given a filename, this will save the current camera position after each completed step of the dynamics. This allows the user to move the camera during a dynamics simulation, and have each position saved so that when the simulation is performed again to make an image sequence, the camera will follow the saved trajectory.
void IVmgr::saveImage | ( | QString | filename | ) |
Given a filename with an appropriate image format file extension, this will render the current scene to an image file. It currently uses a white background and performs anti-aliasing by blending the images from 5 slightly different camera angles. One camera headlight is used for lighting.
void IVmgr::saveImageSequence | ( | const char * | fileStr | ) |
Given a base filename this will save an image of the scene after every completed step of the dynamics. The filename should have a 1 in it, which will be replaced by the simulation time in seconds with a precision of 4 places after the decimal point. The fileStr should also have a valid image format file extension such as .jpg.
void IVmgr::saveNextImage | ( | ) | [slot] |
void IVmgr::selectionCB | ( | void * | , | |
SoPath * | p | |||
) | [static, private] |
void IVmgr::setCamera | ( | double | px, | |
double | py, | |||
double | pz, | |||
double | q1, | |||
double | q2, | |||
double | q3, | |||
double | q4, | |||
double | fd | |||
) |
void IVmgr::setDBMgr | ( | db_planner::DatabaseManager * | ) | [inline] |
void IVmgr::setShiftDown | ( | SbBool | status | ) | [inline, private] |
void IVmgr::setStereoWindow | ( | QWidget * | parent | ) |
void IVmgr::setTool | ( | ToolType | newTool | ) |
void IVmgr::setupPointers | ( | ) | [private] |
void IVmgr::shiftOrCtrlDownCB | ( | void * | , | |
SoEventCallback * | eventCB | |||
) | [static, private] |
void IVmgr::spaceBar | ( | ) | [private] |
void IVmgr::transRot | ( | DraggerInfo * | dInfo | ) | [private] |
This is a callback routine that is invoked anytime a handlebox or centerball is manipulated by the user. It requires a pointer to the draggerInfo structure of the manipulated dragger. If the center of centerball was changed, it simply updates the variable tracking the centerball translation. If a handlebox is moved or a centerball is rotated this computes the new body transform and calls the worldElement::moveTo routine. After the move is completed or a contact prevents further motion, it asks the world to update all grasps, and sets the new dragger position.
void IVmgr::transRotCB | ( | void * | dInfo, | |
SoDragger * | dragger | |||
) | [static, private] |
void IVmgr::unhilightObjContact | ( | int | contactNum | ) |
int IVmgr::useSavedCameraPositions | ( | const char * | filename | ) |
FILE* IVmgr::camerafp [private] |
std::vector<SoBlinker*> IVmgr::contactForceBlinkerVec [private] |
SbBool IVmgr::CtrlDown [private] |
ToolType IVmgr::currTool [private] |
SoSeparator* IVmgr::draggerRoot [private] |
SoMaterial* IVmgr::dynForceMat [private] |
int IVmgr::imgSeqCounter [private] |
const char* IVmgr::imgSeqStr [private] |
IVmgr * IVmgr::ivmgr = 0 [static, private] |
SoSeparator* IVmgr::junk [private] |
db_planner::DatabaseManager* IVmgr::mDBMgr [private] |
StereoViewer* IVmgr::myViewer [private] |
SoSeparator* IVmgr::pointers [private] |
SoSeparator* IVmgr::sceneRoot [private] |
SoSelection* IVmgr::selectionRoot [private] |
SbBool IVmgr::ShiftDown [private] |
SoSeparator* IVmgr::wireFrameRoot [private] |
World* IVmgr::world [private] |