From: <jer...@us...> - 2008-06-27 16:51:59
|
Revision: 6706 http://playerstage.svn.sourceforge.net/playerstage/?rev=6706&view=rev Author: jeremy_asher Date: 2008-06-27 16:52:07 -0700 (Fri, 27 Jun 2008) Log Message: ----------- Reorganized non-essential draw functions to be called from Canvas, fixed menu Modified Paths: -------------- code/stage/trunk/libstage/canvas.cc code/stage/trunk/libstage/model.cc code/stage/trunk/libstage/model_blobfinder.cc code/stage/trunk/libstage/model_camera.cc code/stage/trunk/libstage/model_fiducial.cc code/stage/trunk/libstage/model_laser.cc code/stage/trunk/libstage/model_ranger.cc code/stage/trunk/libstage/option.hh code/stage/trunk/libstage/options_dlg.cc code/stage/trunk/libstage/stage.hh code/stage/trunk/libstage/worldgui.cc Modified: code/stage/trunk/libstage/canvas.cc =================================================================== --- code/stage/trunk/libstage/canvas.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/canvas.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -31,8 +31,9 @@ } - StgCanvas::StgCanvas( StgWorldGui* world, int x, int y, int w, int h) -: Fl_Gl_Window(x,y,w,h) +StgCanvas::StgCanvas( StgWorldGui* world, int x, int y, int w, int h) : +Fl_Gl_Window(x,y,w,h), +ShowFlags( "Flags", true ) { end(); @@ -529,50 +530,78 @@ for( GList* it=selected_models; it; it=it->next ) ((StgModel*)it->data)->DrawSelected(); - // draw the models - if( showflags ) // if any bits are set there's something to draw + + if( showflags & STG_SHOW_FOOTPRINT ) { - if( showflags & STG_SHOW_FOOTPRINT ) + glDisable( GL_DEPTH_TEST ); + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL ); + + for( GList* it=world->StgWorld::children; it; it=it->next ) { - glDisable( GL_DEPTH_TEST ); - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL ); - - for( GList* it=world->StgWorld::children; it; it=it->next ) - { - ((StgModel*)it->data)->DrawTrailFootprint(); - } - glEnable( GL_DEPTH_TEST ); + ((StgModel*)it->data)->DrawTrailFootprint(); } + glEnable( GL_DEPTH_TEST ); + } - if( showflags & STG_SHOW_TRAILRISE ) + if( showflags & STG_SHOW_TRAILRISE ) + { + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL ); + + for( GList* it=world->StgWorld::children; it; it=it->next ) { - glPolygonMode(GL_FRONT_AND_BACK, GL_FILL ); - - for( GList* it=world->StgWorld::children; it; it=it->next ) - { - ((StgModel*)it->data)->DrawTrailBlocks(); - } + ((StgModel*)it->data)->DrawTrailBlocks(); } + } - if( showflags & STG_SHOW_ARROWS ) + if( showflags & STG_SHOW_ARROWS ) + { + glEnable( GL_DEPTH_TEST ); + for( GList* it=world->StgWorld::children; it; it=it->next ) { - glEnable( GL_DEPTH_TEST ); - for( GList* it=world->StgWorld::children; it; it=it->next ) - { - ((StgModel*)it->data)->DrawTrailArrows(); - } + ((StgModel*)it->data)->DrawTrailArrows(); } + } - if( showflags & STG_SHOW_BLOCKS ) - { - DrawBlocks(); + if( showflags & STG_SHOW_BLOCKS ) + { + DrawBlocks(); + } + + //mod->Draw( showflags ); // draw the stuff that changes every update + // draw everything else + if( showflags & STG_SHOW_DATA ) { + for( GList* it=world->StgWorld::children; it; it=it->next ) { + glPushMatrix(); + StgModel* mod = ((StgModel*)it->data); + // move into this model's local coordinate frame + gl_pose_shift( &mod->pose ); + gl_pose_shift( &mod->geom.pose ); + + mod->DataVisualize(); + + glPopMatrix(); } - - //mod->Draw( showflags ); // draw the stuff that changes every update - // draw everything else + } + + if( showflags & STG_SHOW_GRID) { for( GList* it=world->StgWorld::children; it; it=it->next ) - ((StgModel*)it->data)->Draw( showflags, this ); + ((StgModel*)it->data)->DrawGrid(); } + + if( ShowFlags ) { + for( GList* it=world->StgWorld::children; it; it=it->next ) + ((StgModel*)it->data)->DrawFlagList(); + } + + if( StgModel::ShowBlinken ) { + for( GList* it=world->StgWorld::children; it; it=it->next ) + ((StgModel*)it->data)->DrawBlinkenlights(); + } + + if ( StgModel::ShowStatus ) { + for( GList* it=world->StgWorld::children; it; it=it->next ) + ((StgModel*)it->data)->DrawStatus( this ); + } if( world->GetRayList() ) { @@ -590,7 +619,7 @@ glEnable( GL_DEPTH_TEST ); world->ClearRays(); - } + } if( showflags & STG_SHOW_CLOCK ) { Modified: code/stage/trunk/libstage/model.cc =================================================================== --- code/stage/trunk/libstage/model.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/model.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -139,8 +139,7 @@ // static members uint32_t StgModel::count = 0; -Option StgModel::ShowFlags( "Flags", true ); -Option StgModel::ShowVisData( "Sensor Visualizations", false ); +//Option StgModel::ShowVisData( "Sensor Visualizations", false ); Option StgModel::ShowBlinken( "Show Blinkenlights", true ); Option StgModel::ShowStatus( "Show Status", true ); @@ -238,13 +237,10 @@ // now we can add the basic square shape this->AddBlockRect( -0.5,-0.5,1,1 ); - - - RegisterOption( &ShowFlags ); - RegisterOption( &ShowFlags ); - RegisterOption( &ShowVisData ); + + //RegisterOption( &ShowVisData ); RegisterOption( &ShowBlinken ); - RegisterOption( &ShowStatus ); + //RegisterOption( &ShowStatus ); PRINT_DEBUG2( "finished model %s @ %p", this->token, this ); @@ -900,6 +896,12 @@ } void StgModel::DrawStatus( StgCanvas* canvas ) { + glPushMatrix(); + + // move into this model's local coordinate frame + gl_pose_shift( &this->pose ); + gl_pose_shift( &this->geom.pose ); + // draw speech bubble if( say_string ) { @@ -953,6 +955,8 @@ { DrawImage( TextureManager::getInstance()._stall_texture_id, canvas, 0.85 ); } + + glPopMatrix(); } void StgModel::DrawImage( uint32_t texture_id, Stg::StgCanvas* canvas, float alpha ) @@ -1000,25 +1004,22 @@ gl_pose_shift( &this->pose ); gl_pose_shift( &this->geom.pose ); +// if ( ShowVisData ) +// DataVisualize(); +// +// if( gui_grid && (flags & STG_SHOW_GRID) ) +// DrawGrid(); +// +// if( flag_list && ShowFlags ) +// DrawFlagList(); +// +// if( ShowBlinken ) +// DrawBlinkenlights(); +// +// if ( ShowStatus ) { +// DrawStatus( canvas ); +// } - - - if( ShowVisData ) - DataVisualize(); - - if( gui_grid && (flags & STG_SHOW_GRID) ) - DrawGrid(); - - if( flag_list && ShowFlags ) - DrawFlagList(); - - if( ShowBlinken ) - DrawBlinkenlights(); - - if ( ShowStatus ) { - DrawStatus( canvas ); - } - // shift up the CS to the top of this model //gl_coord_shift( 0,0, this->geom.size.z, 0 ); @@ -1030,55 +1031,66 @@ } void StgModel::DrawFlagList( void ) -{ - glPushMatrix(); +{ + if ( flag_list ) { + glPushMatrix(); + + // move into this model's local coordinate frame + gl_pose_shift( &this->pose ); + gl_pose_shift( &this->geom.pose ); - GLUquadric* quadric = gluNewQuadric(); - glTranslatef(0,0,1); // jump up - stg_pose_t gpose = GetGlobalPose(); - glRotatef( 180 + rtod(-gpose.a),0,0,1 ); + GLUquadric* quadric = gluNewQuadric(); + glTranslatef(0,0,1); // jump up + stg_pose_t gpose = GetGlobalPose(); + glRotatef( 180 + rtod(-gpose.a),0,0,1 ); - GList* list = g_list_copy( flag_list ); - list = g_list_reverse(list); + GList* list = g_list_copy( flag_list ); + list = g_list_reverse(list); - for( GList* item = list; item; item = item->next ) - { + for( GList* item = list; item; item = item->next ) + { - StgFlag* flag = (StgFlag*)item->data; + StgFlag* flag = (StgFlag*)item->data; - glTranslatef( 0, 0, flag->size/2.0 ); + glTranslatef( 0, 0, flag->size/2.0 ); - PushColor( flag->color ); - glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); + PushColor( flag->color ); + glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); - gluQuadricDrawStyle( quadric, GLU_FILL ); - gluSphere( quadric, flag->size/2.0, 4,2 ); + gluQuadricDrawStyle( quadric, GLU_FILL ); + gluSphere( quadric, flag->size/2.0, 4,2 ); - // draw the edges darker version of the same color - double r,g,b,a; - stg_color_unpack( flag->color, &r, &g, &b, &a ); - PushColor( stg_color_pack( r/2.0, g/2.0, b/2.0, a )); + // draw the edges darker version of the same color + double r,g,b,a; + stg_color_unpack( flag->color, &r, &g, &b, &a ); + PushColor( stg_color_pack( r/2.0, g/2.0, b/2.0, a )); - gluQuadricDrawStyle( quadric, GLU_LINE ); - gluSphere( quadric, flag->size/2.0, 4,2 ); + gluQuadricDrawStyle( quadric, GLU_LINE ); + gluSphere( quadric, flag->size/2.0, 4,2 ); - PopColor(); - PopColor(); + PopColor(); + PopColor(); - glTranslatef( 0, 0, flag->size/2.0 ); - } + glTranslatef( 0, 0, flag->size/2.0 ); + } - g_list_free( list ); + g_list_free( list ); - gluDeleteQuadric( quadric ); - glPopMatrix(); + gluDeleteQuadric( quadric ); + + glPopMatrix(); + } } void StgModel::DrawBlinkenlights() { glPushMatrix(); + + // move into this model's local coordinate frame + gl_pose_shift( &this->pose ); + gl_pose_shift( &this->geom.pose ); GLUquadric* quadric = gluNewQuadric(); //glTranslatef(0,0,1); // jump up @@ -1145,22 +1157,34 @@ void StgModel::DataVisualize( void ) { - // do nothing - subclasses will do more here + // call DataVisualize on all children + for( GList* it=children; it; it=it->next ) + ((StgModel*)it->data)->DataVisualize(); } void StgModel::DrawGrid( void ) { - stg_bounds3d_t vol; - vol.x.min = -geom.size.x/2.0; - vol.x.max = geom.size.x/2.0; - vol.y.min = -geom.size.y/2.0; - vol.y.max = geom.size.y/2.0; - vol.z.min = 0; - vol.z.max = geom.size.z; + if ( gui_grid ) { + glPushMatrix(); + + // move into this model's local coordinate frame + gl_pose_shift( &this->pose ); + gl_pose_shift( &this->geom.pose ); + + stg_bounds3d_t vol; + vol.x.min = -geom.size.x/2.0; + vol.x.max = geom.size.x/2.0; + vol.y.min = -geom.size.y/2.0; + vol.y.max = geom.size.y/2.0; + vol.z.min = 0; + vol.z.max = geom.size.z; - PushColor( 0,0,1,0.4 ); - gl_draw_grid(vol); - PopColor(); + PushColor( 0,0,1,0.4 ); + gl_draw_grid(vol); + PopColor(); + + glPopMatrix(); + } } bool velocity_is_nonzero( stg_velocity_t* v ) Modified: code/stage/trunk/libstage/model_blobfinder.cc =================================================================== --- code/stage/trunk/libstage/model_blobfinder.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/model_blobfinder.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -363,6 +363,8 @@ glPopMatrix(); + // Call StgModel method to recurse on children + StgModel::DataVisualize(); } Modified: code/stage/trunk/libstage/model_camera.cc =================================================================== --- code/stage/trunk/libstage/model_camera.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/model_camera.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -156,21 +156,21 @@ _canvas->DrawBlocks(); //read depth buffer - glReadPixels(0, 0, _width, _height, - GL_DEPTH_COMPONENT, //GL_RGB, - GL_FLOAT, //GL_UNSIGNED_BYTE, - _frame_data ); +// glReadPixels(0, 0, _width, _height, +// GL_DEPTH_COMPONENT, //GL_RGB, +// GL_FLOAT, //GL_UNSIGNED_BYTE, +// _frame_data ); //transform length into linear length float* data = ( float* )( _frame_data ); //TODO use static_cast here int buf_size = _width * _height; for( int i = 0; i < buf_size; i++ ) - data[ i ] = _camera.realDistance( data[ i ] ); + data[ i ] = 10;//_camera.realDistance( data[ i ] ); //read color buffer - glReadPixels(0, 0, _width, _height, - GL_RGBA, - GL_UNSIGNED_BYTE, - _frame_color_data ); +// glReadPixels(0, 0, _width, _height, +// GL_RGBA, +// GL_UNSIGNED_BYTE, +// _frame_color_data ); glViewport( viewport[0], viewport[1], viewport[2], viewport[3] ); @@ -275,8 +275,8 @@ // glEnd(); glEnable(GL_CULL_FACE); - return; + //TODO see if any of this can be used for the new method //TODO: below this point may no longer be needed if we just draw perfectly square quads based off normal // //draw then camera data @@ -288,6 +288,8 @@ // glPopClientAttrib(); // + // Call StgModel method to recurse on children + StgModel::DataVisualize(); } void StgModelCamera::Draw( uint32_t flags, StgCanvas* canvas ) Modified: code/stage/trunk/libstage/model_fiducial.cc =================================================================== --- code/stage/trunk/libstage/model_fiducial.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/model_fiducial.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -298,7 +298,8 @@ glPopMatrix(); PopColor(); - - } + + // Call StgModel method to recurse on children + StgModel::DataVisualize(); } Modified: code/stage/trunk/libstage/model_laser.cc =================================================================== --- code/stage/trunk/libstage/model_laser.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/model_laser.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -306,6 +306,11 @@ return; glPushMatrix(); + + // move into this model's local coordinate frame + gl_pose_shift( &this->pose ); + gl_pose_shift( &this->geom.pose ); + //glTranslatef( 0,0, 0 ); // shoot the laser beam out at the right height glTranslatef( 0,0, geom.size.z/2.0 ); // shoot the laser beam out at the right height @@ -359,5 +364,9 @@ PopColor(); PopColor(); glDepthMask( GL_TRUE ); + glPopMatrix(); + + // Call StgModel method to recurse on children + StgModel::DataVisualize(); } Modified: code/stage/trunk/libstage/model_ranger.cc =================================================================== --- code/stage/trunk/libstage/model_ranger.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/model_ranger.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -284,103 +284,106 @@ } } - // TODO: configurable ranger noise model - /* - int ranger_noise_test( stg_ranger_sample_t* data, size_t count, ) - { - int s; - for( s=0; s<count; s++ ) - { - // add 10mm random error - ranges[s].range *= 0.1 * drand48(); - } - } - */ +// TODO: configurable ranger noise model +/* + int ranger_noise_test( stg_ranger_sample_t* data, size_t count, ) + { + int s; + for( s=0; s<count; s++ ) + { +// add 10mm random error +ranges[s].range *= 0.1 * drand48(); +} +} + */ - void StgModelRanger::Print( char* prefix ) - { - StgModel::Print( prefix ); +void StgModelRanger::Print( char* prefix ) +{ + StgModel::Print( prefix ); - printf( "\tRanges[ " ); + printf( "\tRanges[ " ); - for( unsigned int i=0; i<sensor_count; i++ ) - printf( "%.2f ", samples[i] ); - puts( " ]" ); - } + for( unsigned int i=0; i<sensor_count; i++ ) + printf( "%.2f ", samples[i] ); + puts( " ]" ); +} - void StgModelRanger::DataVisualize( void ) - { - if( ! (samples && sensors && sensor_count) ) - return; +void StgModelRanger::DataVisualize( void ) +{ + if( ! (samples && sensors && sensor_count) ) + return; - glPushMatrix(); + glPushMatrix(); - // move into this model's local coordinate frame - gl_pose_shift( &this->pose ); - gl_pose_shift( &this->geom.pose ); + // move into this model's local coordinate frame + gl_pose_shift( &this->pose ); + gl_pose_shift( &this->geom.pose ); - // if all models have the same number of sensors, this is fast - // as it will probably not use a system call or cause a cache - // miss - static float* pts = NULL; - size_t memsize = 9 * sensor_count * sizeof(float); - pts = (float*)g_realloc( pts, memsize ); - bzero( pts, memsize ); + // if all models have the same number of sensors, this is fast + // as it will probably not use a system call or cause a cache + // miss + static float* pts = NULL; + size_t memsize = 9 * sensor_count * sizeof(float); + pts = (float*)g_realloc( pts, memsize ); + bzero( pts, memsize ); - //glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); - //PushColor( 0,0,0,1 ); + //glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); + //PushColor( 0,0,0,1 ); - // calculate a triangle for each non-zero sensor range - for( unsigned int s=0; s<sensor_count; s++ ) + // calculate a triangle for each non-zero sensor range + for( unsigned int s=0; s<sensor_count; s++ ) + { + if( samples[s] > 0.0 ) { - if( samples[s] > 0.0 ) - { - stg_ranger_sensor_t* rngr = &sensors[s]; + stg_ranger_sensor_t* rngr = &sensors[s]; - //double dx = rngr->size.x/2.0; - //double dy = rngr->size.y/2.0; - //double dz = rngr->size.z/2.0; + //double dx = rngr->size.x/2.0; + //double dy = rngr->size.y/2.0; + //double dz = rngr->size.z/2.0; - // DEBUG: draw a point for the sensor pose - glPointSize( 6 ); - glBegin( GL_POINTS ); - glVertex3f( rngr->pose.x, rngr->pose.y, rngr->pose.z ); - glEnd(); + // DEBUG: draw a point for the sensor pose + glPointSize( 6 ); + glBegin( GL_POINTS ); + glVertex3f( rngr->pose.x, rngr->pose.y, rngr->pose.z ); + glEnd(); - // sensor FOV - double sidelen = samples[s]; - double da = rngr->fov/2.0; + // sensor FOV + double sidelen = samples[s]; + double da = rngr->fov/2.0; - unsigned int index = s*9; - pts[index+0] = rngr->pose.x; - pts[index+1] = rngr->pose.y; - pts[index+2] = rngr->pose.z; + unsigned int index = s*9; + pts[index+0] = rngr->pose.x; + pts[index+1] = rngr->pose.y; + pts[index+2] = rngr->pose.z; - pts[index+3] = rngr->pose.x + sidelen*cos(rngr->pose.a - da ); - pts[index+4] = rngr->pose.y + sidelen*sin(rngr->pose.a - da ); - pts[index+5] = rngr->pose.z; + pts[index+3] = rngr->pose.x + sidelen*cos(rngr->pose.a - da ); + pts[index+4] = rngr->pose.y + sidelen*sin(rngr->pose.a - da ); + pts[index+5] = rngr->pose.z; - pts[index+6] = rngr->pose.x + sidelen*cos(rngr->pose.a + da ); - pts[index+7] = rngr->pose.y + sidelen*sin(rngr->pose.a + da ); - pts[index+8] = rngr->pose.z; - } + pts[index+6] = rngr->pose.x + sidelen*cos(rngr->pose.a + da ); + pts[index+7] = rngr->pose.y + sidelen*sin(rngr->pose.a + da ); + pts[index+8] = rngr->pose.z; } + } - //PopColor(); + //PopColor(); - // draw the filled triangles in transparent blue - glDepthMask( GL_FALSE ); - glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); - PushColor( 0, 1, 0, 0.1 ); // transparent pale green - glEnableClientState( GL_VERTEX_ARRAY ); - glVertexPointer( 3, GL_FLOAT, 0, pts ); - glDrawArrays( GL_TRIANGLES, 0, 3 * sensor_count ); + // draw the filled triangles in transparent blue + glDepthMask( GL_FALSE ); + glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); + PushColor( 0, 1, 0, 0.1 ); // transparent pale green + glEnableClientState( GL_VERTEX_ARRAY ); + glVertexPointer( 3, GL_FLOAT, 0, pts ); + glDrawArrays( GL_TRIANGLES, 0, 3 * sensor_count ); - // restore state - glDepthMask( GL_TRUE ); - PopColor(); + // restore state + glDepthMask( GL_TRUE ); + PopColor(); + + glPopMatrix(); + + // Call StgModel method to recurse on children + StgModel::DataVisualize(); +} - glPopMatrix(); - } - Modified: code/stage/trunk/libstage/option.hh =================================================================== --- code/stage/trunk/libstage/option.hh 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/option.hh 2008-06-27 23:52:07 UTC (rev 6706) @@ -1,3 +1,11 @@ +/** option.hh + Class that encapsulates a boolean and pairs it with a string description + Used to pass settings between the GUI and the drawing classes + + Author: Jeremy Asher +*/ + + #ifndef _OPTION_H_ #define _OPTION_H_ @@ -9,7 +17,6 @@ class Option { private: friend bool compare( const Option* lhs, const Option* rhs ); - friend std::ostream& operator<<( std::ostream& os, const Option& opt ); std::string optName; bool value; @@ -24,13 +31,6 @@ void set( bool val ) { value = val; } }; -// std::ostream& operator<<( std::ostream& os, const Option& opt ) { -// os<<opt.optName; -// os<<": "; -// os<<opt.value; -// return os; -// } -// // Comparator to dereference Option pointers and compare their strings struct optComp { inline bool operator()( const Option* lhs, const Option* rhs ) const Modified: code/stage/trunk/libstage/options_dlg.cc =================================================================== --- code/stage/trunk/libstage/options_dlg.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/options_dlg.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -4,7 +4,7 @@ namespace Stg { OptionsDlg::OptionsDlg( int x, int y, int w, int h ) : - Fl_Window( x,y, w,h, "Sensor Options" ), + Fl_Window( x,y, w,h, "Options" ), changedItem( NULL ), showAll( NULL ), status( NO_EVENT ), Modified: code/stage/trunk/libstage/stage.hh =================================================================== --- code/stage/trunk/libstage/stage.hh 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/stage.hh 2008-06-27 23:52:07 UTC (rev 6706) @@ -1165,14 +1165,12 @@ static uint32_t count; static GHashTable* modelsbyid; - // Draw options - std::vector<Option*> drawOptions; - static Option ShowFlags; - static Option ShowVisData; + std::vector<Option*> drawOptions; + +public: + // Draw Options static Option ShowBlinken; static Option ShowStatus; - -public: /** Look up a model pointer by a unique model ID */ static StgModel* LookupId( uint32_t id ) @@ -1240,6 +1238,7 @@ int gui_outline; int gui_mask; + /// Register an Option for pickup by the GUI void RegisterOption( Option* opt ) { drawOptions.push_back( opt ); } @@ -1961,6 +1960,8 @@ void DrawRays(); void ClearRays(); void DrawGlobalGrid(); + + Option ShowFlags; public: Modified: code/stage/trunk/libstage/worldgui.cc =================================================================== --- code/stage/trunk/libstage/worldgui.cc 2008-06-27 21:54:18 UTC (rev 6705) +++ code/stage/trunk/libstage/worldgui.cc 2008-06-27 23:52:07 UTC (rev 6706) @@ -110,18 +110,19 @@ #include <set> -static const char* MITEM_VIEW_DATA = "&View/&Display Sensor Data"; -static const char* MITEM_VIEW_BLOCKS = "&View/&Blocks"; -static const char* MITEM_VIEW_GRID = "&View/&Grid"; -static const char* MITEM_VIEW_OCCUPANCY = "&View/&Occupancy"; -static const char* MITEM_VIEW_QUADTREE = "&View/&Tree"; -static const char* MITEM_VIEW_FOLLOW = "&View/&Follow"; -static const char* MITEM_VIEW_CLOCK = "&View/&Clock"; -static const char* MITEM_VIEW_FOOTPRINTS = "&View/T&rails/&Footprints"; -static const char* MITEM_VIEW_BLOCKSRISING = "&View/T&rails/&Blocks rising"; -static const char* MITEM_VIEW_ARROWS = "&View/T&rails/&Arrows rising"; -static const char* MITEM_VIEW_TRAILS = "&View/&Trail"; -static const char* MITEM_VIEW_STATUS = "&View/&Status"; +static const char* MITEM_VIEW_DATA = "&View/&Display sensor data"; +static const char* MITEM_VIEW_BLOCKS = "&View/Blocks"; +static const char* MITEM_VIEW_FLAGS = "&View/Flags"; +static const char* MITEM_VIEW_GRID = "&View/Grid"; +static const char* MITEM_VIEW_OCCUPANCY = "&View/Occupancy"; +static const char* MITEM_VIEW_QUADTREE = "&View/Tree"; +static const char* MITEM_VIEW_FOLLOW = "&View/Follow selected"; +static const char* MITEM_VIEW_CLOCK = "&View/Clock"; +static const char* MITEM_VIEW_FOOTPRINTS = "&View/Trails/Footprints"; +static const char* MITEM_VIEW_BLOCKSRISING = "&View/Trails/Blocks rising"; +static const char* MITEM_VIEW_ARROWS = "&View/Trails/Arrows rising"; +static const char* MITEM_VIEW_TRAILS = "&View/Trail"; +static const char* MITEM_VIEW_STATUS = "&View/Status"; static const char* MITEM_VIEW_PERSPECTIVE = "&View/Perspective camera"; // this should be set by CMake @@ -160,16 +161,17 @@ mbar->add( "File/E&xit", FL_CTRL+'q', StgWorldGui::fileExitCb, this ); mbar->add( "&View", 0, 0, 0, FL_SUBMENU ); - mbar->add( MITEM_VIEW_DATA, 'd', StgWorldGui::viewToggleCb, canvas, + mbar->add( MITEM_VIEW_DATA, 'd', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_DATA ? FL_MENU_VALUE : 0 )); - mbar->add( "View/&Sensor options...", FL_CTRL + 'o', StgWorldGui::viewOptionsCb, this, FL_MENU_DIVIDER ); - mbar->add( MITEM_VIEW_BLOCKS, 'b', StgWorldGui::viewToggleCb, canvas, + mbar->add( MITEM_VIEW_BLOCKS, 'b', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_BLOCKS ? FL_MENU_VALUE : 0 )); - mbar->add( MITEM_VIEW_GRID, 'g', StgWorldGui::viewToggleCb, canvas, + mbar->add( MITEM_VIEW_FLAGS, 0, StgWorldGui::viewToggleCb, canvas, + FL_MENU_TOGGLE| (canvas->ShowFlags ? FL_MENU_VALUE : 0 )); + mbar->add( MITEM_VIEW_GRID, 'g', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_GRID ? FL_MENU_VALUE : 0 )); - mbar->add( MITEM_VIEW_OCCUPANCY, FL_ALT+'o', StgWorldGui::viewToggleCb, canvas, + mbar->add( MITEM_VIEW_OCCUPANCY, 'o', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_OCCUPANCY ? FL_MENU_VALUE : 0 )); - mbar->add( MITEM_VIEW_QUADTREE, FL_ALT+'t', StgWorldGui::viewToggleCb, canvas, + mbar->add( MITEM_VIEW_QUADTREE, FL_CTRL +'t', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_QUADTREE ? FL_MENU_VALUE : 0 )); mbar->add( MITEM_VIEW_FOLLOW, 'f', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_FOLLOW ? FL_MENU_VALUE : 0 )); @@ -177,17 +179,17 @@ FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_CLOCK ? FL_MENU_VALUE : 0 )); mbar->add( MITEM_VIEW_PERSPECTIVE, 'r', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->use_perspective_camera )); + mbar->add( MITEM_VIEW_STATUS, 's', StgWorldGui::viewToggleCb, canvas, + FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_STATUS ? FL_MENU_VALUE : 0 )); mbar->add( MITEM_VIEW_TRAILS, 't', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_TRAILS ? FL_MENU_VALUE : 0 )); - mbar->add( MITEM_VIEW_STATUS, 's', StgWorldGui::viewToggleCb, canvas, - FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_STATUS ? FL_MENU_VALUE : 0 )); mbar->add( MITEM_VIEW_FOOTPRINTS, FL_CTRL+'f', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_FOOTPRINT ? FL_MENU_VALUE : 0 )); mbar->add( MITEM_VIEW_ARROWS, FL_CTRL+'a', StgWorldGui::viewToggleCb, canvas, FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_ARROWS ? FL_MENU_VALUE : 0 )); mbar->add( MITEM_VIEW_BLOCKSRISING, FL_CTRL+'t', StgWorldGui::viewToggleCb, canvas, - FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_TRAILRISE ? FL_MENU_VALUE : 0 )); - + FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_TRAILRISE ? FL_MENU_VALUE : 0 ) | FL_MENU_DIVIDER); + mbar->add( "View/Additional options...", FL_CTRL + 'o', StgWorldGui::viewOptionsCb, this ); mbar->add( "&Help", 0, 0, 0, FL_SUBMENU ); @@ -543,6 +545,7 @@ else if( strcmp(picked, MITEM_VIEW_TRAILS ) == 0 ) canvas->InvertView( STG_SHOW_TRAILS ); else if( strcmp(picked, MITEM_VIEW_BLOCKSRISING ) == 0 ) canvas->InvertView( STG_SHOW_TRAILRISE ); else if( strcmp(picked, MITEM_VIEW_STATUS ) == 0 ) canvas->InvertView( STG_SHOW_STATUS ); + else if( strcmp(picked, MITEM_VIEW_FLAGS ) == 0 ) canvas->ShowFlags.set( !canvas->ShowFlags ); else if( strcmp(picked, MITEM_VIEW_PERSPECTIVE ) == 0 ) { canvas->use_perspective_camera = ! canvas->use_perspective_camera; canvas->invalidate(); } else PRINT_ERR1( "Unrecognized menu item \"%s\" not handled", picked ); This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |