Revision: 6707
          http://playerstage.svn.sourceforge.net/playerstage/?rev=6707&view=rev
Author:   rtv
Date:     2008-06-28 17:35:54 -0700 (Sat, 28 Jun 2008)

Log Message:
-----------
extended option class to manage menus nicely, plus revised visualization tree 
logic

Modified Paths:
--------------
    code/stage/trunk/libstage/CMakeLists.txt
    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/options_dlg.hh
    code/stage/trunk/libstage/stage.hh
    code/stage/trunk/libstage/worldfile.hh
    code/stage/trunk/libstage/worldgui.cc
    code/stage/trunk/worlds/everything.world
    code/stage/trunk/worlds/fasr.world

Added Paths:
-----------
    code/stage/trunk/libstage/option.cc

Modified: code/stage/trunk/libstage/CMakeLists.txt
===================================================================
--- code/stage/trunk/libstage/CMakeLists.txt    2008-06-27 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/CMakeLists.txt    2008-06-29 00:35:54 UTC (rev 
6707)
@@ -28,6 +28,7 @@
        resource.cc
        texture_manager.cc
        option.hh
+       option.cc
        options_dlg.cc
        options_dlg.hh
 )

Modified: code/stage/trunk/libstage/canvas.cc
===================================================================
--- code/stage/trunk/libstage/canvas.cc 2008-06-27 23:52:07 UTC (rev 6706)
+++ code/stage/trunk/libstage/canvas.cc 2008-06-29 00:35:54 UTC (rev 6707)
@@ -32,8 +32,20 @@
 
 
 StgCanvas::StgCanvas( StgWorldGui* world, int x, int y, int w, int h) :
-Fl_Gl_Window(x,y,w,h),
-ShowFlags( "Flags", true )
+  Fl_Gl_Window(x,y,w,h),
+  showBlinken( "Blinkenlights", "show_blinkenlights", "", true ),
+  showBlocks( "Blocks", "show_blocks", "b", true  ),
+  showClock( "Clock", "show_clock", "c", true ),
+  showData( "Data", "show_data", "d", false ),
+  showFlags( "Flags", "show_flags", "f",  true ),
+  showFollow( "Follow", "show_follow", "F", false ),
+  showFootprints( "Footprints", "show_footprints", "f", false ),
+  showGrid( "Grid", "show_grid", "g", true ),
+  showTrailArrows( "Trails/Rising Arrows", "show_trailarrows", "#a", false ),
+  showTrailRise( "Trails/Rising blocks", "show_trailrise", "#r", false ),
+  showTrails( "Trails/Fast", "show_trailfast", "t", false ),
+  showTree( "Debug/Tree", "show_tree", "#T", false ),
+  showOccupancy( "Debug/Occupancy", "show_occupancy", "#O", false )
 {
        end();
 
@@ -57,8 +69,6 @@
        dragging = false;
        rotating = false;
 
-       showflags = STG_SHOW_CLOCK | STG_SHOW_BLOCKS | STG_SHOW_GRID | 
STG_SHOW_DATA | STG_SHOW_STATUS;
-
        // // start the timer that causes regular redraws
        Fl::add_timeout( ((double)interval/1000), 
                                                  
(Fl_Timeout_Handler)StgCanvas::TimerCallback, 
@@ -69,21 +79,6 @@
 {
 }
 
-void StgCanvas::InvertView( uint32_t invertflags )
-{
-       showflags = (showflags ^ invertflags);
-
-       //   printf( "flags %u data %d grid %d blocks %d follow %d clock %d 
tree %d occ %d\n",
-       //        showflags, 
-       //        showflags & STG_SHOW_DATA,
-       //        showflags & STG_SHOW_GRID,
-       //        showflags & STG_SHOW_BLOCKS,
-       //        showflags & STG_SHOW_FOLLOW,
-       //        showflags & STG_SHOW_CLOCK,
-       //        showflags & STG_SHOW_QUADTREE,
-       //        showflags & STG_SHOW_OCCUPANCY );
-}
-
 StgModel* StgCanvas::Select( int x, int y )
 {
   // TODO XX
@@ -483,7 +478,7 @@
                if( mod->rebuild_displaylist )
                {
                        //printf( "Model %s is dirty\n", mod->Token() );        
                                 
-                       mod->BuildDisplayList( showflags ); // ready to be 
rendered
+                       mod->BuildDisplayList(); // ready to be rendered
                }
                
                // move into this model's local coordinate frame
@@ -501,128 +496,107 @@
 
 void StgCanvas::renderFrame()
 {
-       if( ! (showflags & STG_SHOW_TRAILS) )
-               glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
-       
-       if( showflags & STG_SHOW_GRID )
-               DrawGlobalGrid();
-
-
-       if( (showflags & STG_SHOW_QUADTREE) || (showflags & STG_SHOW_OCCUPANCY) 
)
-       {
-         glPushMatrix();         
-         glScalef( 1.0/world->Resolution(), 1.0/world->Resolution(), 0 );
-         
-         glLineWidth( 1 );
-         glPolygonMode( GL_FRONT, GL_LINE );
-         colorstack.Push(1,0,0);
-         
-         if( showflags & STG_SHOW_OCCUPANCY )
-                ((StgWorldGui*)world)->DrawTree( false );
-         
-         if( showflags & STG_SHOW_QUADTREE )
-                ((StgWorldGui*)world)->DrawTree( true );
-         
-         colorstack.Pop();
-         glPopMatrix();
-       }
-       
-       for( GList* it=selected_models; it; it=it->next )
-               ((StgModel*)it->data)->DrawSelected();
-       
-
-       if( showflags & STG_SHOW_FOOTPRINT )
-       {
+  if( ! showTrails )
+        glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
+  
+  if( showGrid )
+        DrawGlobalGrid();
+  
+  if( showTree || showOccupancy )
+        {
+               glPushMatrix();   
+               glScalef( 1.0/world->Resolution(), 1.0/world->Resolution(), 0 );
+               
+               glLineWidth( 1 );
+               glPolygonMode( GL_FRONT, GL_LINE );
+               colorstack.Push(1,0,0);
+               
+               if( showOccupancy )
+                 ((StgWorldGui*)world)->DrawTree( false );
+               
+               if( showTree )
+                 ((StgWorldGui*)world)->DrawTree( true );
+               
+               colorstack.Pop();
+               glPopMatrix();
+        }
+  
+  for( GList* it=selected_models; it; it=it->next )
+        ((StgModel*)it->data)->DrawSelected();
+  
+  if( showFootprints )
+        {
                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();
-               }
+                 {
+                        ((StgModel*)it->data)->DrawTrailFootprint();
+                 }
                glEnable( GL_DEPTH_TEST );
-       }
-
-       if( showflags & STG_SHOW_TRAILRISE )
-       {
+        }
+  
+  if( showTrailRise )
+        {
                glPolygonMode(GL_FRONT_AND_BACK, GL_FILL );
-
+               
                for( GList* it=world->StgWorld::children; it; it=it->next )
-               {
-                       ((StgModel*)it->data)->DrawTrailBlocks();
-               }
-       }
-
-       if( showflags & STG_SHOW_ARROWS )
-       {
+                 {
+                        ((StgModel*)it->data)->DrawTrailBlocks();
+                 }
+        }
+  
+  if( showTrailArrows )
+        {
                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();
-       }
-
-       //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();
-               }
-       }
+  if( showBlocks )
+        DrawBlocks();
+  
+  // draw the model-specific visualizations
+  if( showData ) 
+        for( GList* it=world->StgWorld::children; it; it=it->next ) 
+               ((StgModel*)it->data)->DataVisualizeTree();  
+  
+       if( showGrid ) 
+         for( GList* it=world->StgWorld::children; it; it=it->next )
+                ((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( showflags & STG_SHOW_GRID) {
-               for( GList* it=world->StgWorld::children; it; it=it->next )
-                       ((StgModel*)it->data)->DrawGrid();
-       }
+       if ( StgModel::ShowStatus )
+         for( GList* it=world->StgWorld::children; it; it=it->next )
+                ((StgModel*)it->data)->DrawStatus( this );
        
-       if( ShowFlags ) {
-               for( GList* it=world->StgWorld::children; it; it=it->next )
-                       ((StgModel*)it->data)->DrawFlagList();
-       }
+       if( world->GetRayList() )
+         {
+                glDisable( GL_DEPTH_TEST );
+                PushColor( 0,0,0,0.5 );
+                for( GList* it = world->GetRayList(); it; it=it->next )
+                       {
+                         float* pts = (float*)it->data;
+                         glBegin( GL_LINES );
+                         glVertex2f( pts[0], pts[1] );
+                         glVertex2f( pts[2], pts[3] );
+                         glEnd();
+                       }  
+                PopColor();
+                glEnable( GL_DEPTH_TEST );
+                
+                world->ClearRays();
+         } 
        
-       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() )
+       if( showClock )
        {
-               glDisable( GL_DEPTH_TEST );
-               PushColor( 0,0,0,0.5 );
-               for( GList* it = world->GetRayList(); it; it=it->next )
-               {
-                       float* pts = (float*)it->data;
-                       glBegin( GL_LINES );
-                       glVertex2f( pts[0], pts[1] );
-                       glVertex2f( pts[2], pts[3] );
-                       glEnd();
-               }  
-               PopColor();
-               glEnable( GL_DEPTH_TEST );
-
-               world->ClearRays();
-       } 
-
-       if( showflags & STG_SHOW_CLOCK )
-       {
                //use orthogonal projeciton without any zoom
                glMatrixMode (GL_PROJECTION);
                glPushMatrix(); //save old projection
@@ -717,6 +691,74 @@
 }
 
 
+void StgCanvas::CreateMenuItems( Fl_Menu_Bar* menu, std::string path )
+{
+  showData.CreateMenuItem( menu, path );
+  showBlocks.CreateMenuItem( menu, path );
+  showFlags.CreateMenuItem( menu, path );
+  showClock.CreateMenuItem( menu, path );
+  showFlags.CreateMenuItem( menu, path );
+  showFollow.CreateMenuItem( menu, path );
+  showFootprints.CreateMenuItem( menu, path );
+  showGrid.CreateMenuItem( menu, path );
+  showOccupancy.CreateMenuItem( menu, path );
+  showTrailArrows.CreateMenuItem( menu, path );
+  showTrails.CreateMenuItem( menu, path );
+  showTrailRise.CreateMenuItem( menu, path );  
+  showTree.CreateMenuItem( menu, path );  
+}
+
+
+void StgCanvas::Load( Worldfile* wf, int sec )
+{
+  float x = wf->ReadTupleFloat(sec, "center", 0, 0 );
+  float y = wf->ReadTupleFloat(sec, "center", 1, 0 );
+  camera.setPose( x, y );
+  
+  camera.setPitch( wf->ReadTupleFloat( sec, "rotate", 0, 0 ) );
+  camera.setYaw( wf->ReadTupleFloat( sec, "rotate", 1, 0 ) );
+  camera.setScale( wf->ReadFloat(sec, "scale", camera.getScale() ) );
+  interval = wf->ReadInt(sec, "interval", interval );
+  
+  showData.Load( wf, sec );
+  showBlocks.Load( wf, sec );
+  showClock.Load( wf, sec );
+  showFollow.Load( wf, sec );
+  showFootprints.Load( wf, sec );
+  showGrid.Load( wf, sec );
+  showOccupancy.Load( wf, sec );
+  showTrailArrows.Load( wf, sec );
+  showTrailRise.Load( wf, sec );
+  showTrails.Load( wf, sec );
+  showTree.Load( wf, sec );
+
+  invalidate(); // we probably changed something
+}
+
+void StgCanvas::Save( Worldfile* wf, int sec )
+{
+  wf->WriteFloat( sec, "scale", camera.getScale() );
+  
+  wf->WriteTupleFloat( sec, "center", 0, camera.getX() );
+  wf->WriteTupleFloat( sec, "center", 1, camera.getY() );
+  
+  wf->WriteTupleFloat( sec, "rotate", 0, camera.getPitch()  );
+  wf->WriteTupleFloat( sec, "rotate", 1, camera.getYaw()  );
+  
+  showData.Save( wf, sec );
+  showBlocks.Save( wf, sec );
+  showClock.Save( wf, sec );
+  showFollow.Save( wf, sec );
+  showFootprints.Save( wf, sec );
+  showGrid.Save( wf, sec );
+  showOccupancy.Save( wf, sec );
+  showTrailArrows.Save( wf, sec );
+  showTrailRise.Save( wf, sec );
+  showTrails.Save( wf, sec );
+  showTree.Save( wf, sec );
+}
+
+
 void StgCanvas::draw()
 {
        static bool loaded_texture = false;
@@ -811,7 +853,7 @@
 
        
        if( use_perspective_camera == true ) {
-               if( (showflags & STG_SHOW_FOLLOW)  && last_selection ) {
+               if( showFollow  && last_selection ) {
                        //Follow the selected robot
                        stg_pose_t gpose = last_selection->GetGlobalPose();
                        perspective_camera.setPose( gpose.x, gpose.y, 0.2 );
@@ -819,7 +861,7 @@
                        
                }
                perspective_camera.Draw();
-       } else if( (showflags & STG_SHOW_FOLLOW)  && last_selection ) {
+       } else if( showFollow  && last_selection ) {
                //Follow the selected robot
                stg_pose_t gpose = last_selection->GetGlobalPose();
                camera.setPose( gpose.x, gpose.y );

Modified: code/stage/trunk/libstage/model.cc
===================================================================
--- code/stage/trunk/libstage/model.cc  2008-06-27 23:52:07 UTC (rev 6706)
+++ code/stage/trunk/libstage/model.cc  2008-06-29 00:35:54 UTC (rev 6707)
@@ -110,38 +110,38 @@
 
 
 //static const members
-const bool StgModel::DEFAULT_BLOBRETURN = true;
-const bool StgModel::DEFAULT_BOUNDARY = false;
-const stg_color_t StgModel::DEFAULT_COLOR = (0xFFFF0000); // solid red
-const stg_joules_t StgModel::DEFAULT_ENERGY_CAPACITY = 1000.0;
-const bool StgModel::DEFAULT_ENERGY_CHARGEENABLE = true;
-const stg_watts_t StgModel::DEFAULT_ENERGY_GIVERATE =  0.0;
-const stg_meters_t StgModel::DEFAULT_ENERGY_PROBERANGE = 0.0;
-const stg_watts_t StgModel::DEFAULT_ENERGY_TRICKLERATE = 0.1;
-const stg_meters_t StgModel::DEFAULT_GEOM_SIZEX = 0.10;
-const stg_meters_t StgModel::DEFAULT_GEOM_SIZEY = 0.10;
-const stg_meters_t StgModel::DEFAULT_GEOM_SIZEZ = 0.10;
-const bool StgModel::DEFAULT_GRID = false;
-const bool StgModel::DEFAULT_GRIPPERRETURN = false;
-const stg_laser_return_t StgModel::DEFAULT_LASERRETURN = LaserVisible;
-const stg_meters_t StgModel::DEFAULT_MAP_RESOLUTION = 0.1;
-const stg_movemask_t StgModel::DEFAULT_MASK = (STG_MOVE_TRANS | STG_MOVE_ROT);
-const stg_kg_t StgModel::DEFAULT_MASS = 10.0;
-const bool StgModel::DEFAULT_NOSE = false;
-const bool StgModel::DEFAULT_OBSTACLERETURN = true;
-const bool StgModel::DEFAULT_OUTLINE = true;
-const bool StgModel::DEFAULT_RANGERRETURN = true;
+static const bool DEFAULT_BLOBRETURN = true;
+static const bool DEFAULT_BOUNDARY = false;
+static const stg_color_t DEFAULT_COLOR = (0xFFFF0000); // solid red
+static const stg_joules_t DEFAULT_ENERGY_CAPACITY = 1000.0;
+static const bool DEFAULT_ENERGY_CHARGEENABLE = true;
+static const stg_watts_t DEFAULT_ENERGY_GIVERATE =  0.0;
+static const stg_meters_t DEFAULT_ENERGY_PROBERANGE = 0.0;
+static const stg_watts_t DEFAULT_ENERGY_TRICKLERATE = 0.1;
+static const stg_meters_t DEFAULT_GEOM_SIZEX = 0.10;
+static const stg_meters_t DEFAULT_GEOM_SIZEY = 0.10;
+static const stg_meters_t DEFAULT_GEOM_SIZEZ = 0.10;
+static const bool DEFAULT_GRID = false;
+static const bool DEFAULT_GRIPPERRETURN = false;
+static const stg_laser_return_t DEFAULT_LASERRETURN = LaserVisible;
+static const stg_meters_t DEFAULT_MAP_RESOLUTION = 0.1;
+static const stg_movemask_t DEFAULT_MASK = (STG_MOVE_TRANS | STG_MOVE_ROT);
+static const stg_kg_t DEFAULT_MASS = 10.0;
+static const bool DEFAULT_NOSE = false;
+static const bool DEFAULT_OBSTACLERETURN = true;
+static const bool DEFAULT_OUTLINE = true;
+static const bool DEFAULT_RANGERRETURN = true;
 
 // speech bubble colors
-const stg_color_t StgModel::BUBBLE_FILL = 0xFFC8C8FF; // light blue/grey
-const stg_color_t StgModel::BUBBLE_BORDER = 0xFF000000; // black
-const stg_color_t StgModel::BUBBLE_TEXT = 0xFF000000; // black
+static const stg_color_t BUBBLE_FILL = 0xFFC8C8FF; // light blue/grey
+static const stg_color_t BUBBLE_BORDER = 0xFF000000; // black
+static const stg_color_t BUBBLE_TEXT = 0xFF000000; // black
 
 // static members
 uint32_t StgModel::count = 0;
 //Option StgModel::ShowVisData( "Sensor Visualizations", false );
-Option StgModel::ShowBlinken( "Show Blinkenlights", true );
-Option StgModel::ShowStatus( "Show Status", true );
+Option StgModel::ShowBlinken( "Show Blinkenlights", "show_blinkenlights", "", 
true );
+Option StgModel::ShowStatus( "Show Status", "show_status", "", true );
 
 GHashTable* StgModel::modelsbyid = g_hash_table_new( NULL, NULL );
 
@@ -196,23 +196,23 @@
 
        this->displaylist = 0;
 
-       this->geom.size.x = StgModel::DEFAULT_GEOM_SIZEX;
-       this->geom.size.y = StgModel::DEFAULT_GEOM_SIZEX;
-       this->geom.size.z = StgModel::DEFAULT_GEOM_SIZEX;
+       this->geom.size.x = DEFAULT_GEOM_SIZEX;
+       this->geom.size.y = DEFAULT_GEOM_SIZEX;
+       this->geom.size.z = DEFAULT_GEOM_SIZEX;
        memset( &this->geom.pose, 0, sizeof(this->geom.pose));
 
-       this->obstacle_return = StgModel::DEFAULT_OBSTACLERETURN;
-       this->ranger_return = StgModel::DEFAULT_RANGERRETURN;
-       this->blob_return = StgModel::DEFAULT_BLOBRETURN;
-       this->laser_return = StgModel::DEFAULT_LASERRETURN;
-       this->gripper_return = StgModel::DEFAULT_GRIPPERRETURN;
-       this->boundary = StgModel::DEFAULT_BOUNDARY;
-       this->color = StgModel::DEFAULT_COLOR;
-       this->map_resolution = StgModel::DEFAULT_MAP_RESOLUTION; // meters
-       this->gui_nose = StgModel::DEFAULT_NOSE;
-       this->gui_grid = StgModel::DEFAULT_GRID;
-       this->gui_outline = StgModel::DEFAULT_OUTLINE;
-       this->gui_mask = this->parent ? 0 : StgModel::DEFAULT_MASK;
+       this->obstacle_return = DEFAULT_OBSTACLERETURN;
+       this->ranger_return = DEFAULT_RANGERRETURN;
+       this->blob_return = DEFAULT_BLOBRETURN;
+       this->laser_return = DEFAULT_LASERRETURN;
+       this->gripper_return = DEFAULT_GRIPPERRETURN;
+       this->boundary = DEFAULT_BOUNDARY;
+       this->color = DEFAULT_COLOR;
+       this->map_resolution = DEFAULT_MAP_RESOLUTION; // meters
+       this->gui_nose = DEFAULT_NOSE;
+       this->gui_grid = DEFAULT_GRID;
+       this->gui_outline = DEFAULT_OUTLINE;
+       this->gui_mask = this->parent ? 0 : DEFAULT_MASK;
 
        this->fiducial_return = 0;
        this->fiducial_key = 0;
@@ -1146,7 +1146,7 @@
        glPopMatrix(); // drop out of local coords
 }
 
-void StgModel::BuildDisplayList( uint32_t flags )
+void StgModel::BuildDisplayList()
 {
        glNewList( displaylist, GL_COMPILE );   
        DrawBlocks();
@@ -1156,12 +1156,28 @@
 }
 
 void StgModel::DataVisualize( void )
+{  
+  // do nothing
+}
+
+void StgModel::DataVisualizeTree( void )
 {
-       // call DataVisualize on all children
-       for( GList* it=children; it; it=it->next )
-               ((StgModel*)it->data)->DataVisualize();
+  // move into this model's local coordinate frame
+  glPushMatrix();
+  gl_pose_shift( &pose );
+  gl_pose_shift( &geom.pose );
+  
+  DataVisualize(); // virtual function overridden by most model types
+  
+  // recurse on children
+  for( GList* it=children; it; it=it->next )
+        ((StgModel*)it->data)->DataVisualizeTree();
+  
+  // leave the local CF
+  glPopMatrix();
 }
 
+
 void StgModel::DrawGrid( void )
 {
        if ( gui_grid ) {

Modified: code/stage/trunk/libstage/model_blobfinder.cc
===================================================================
--- code/stage/trunk/libstage/model_blobfinder.cc       2008-06-27 23:52:07 UTC 
(rev 6706)
+++ code/stage/trunk/libstage/model_blobfinder.cc       2008-06-29 00:35:54 UTC 
(rev 6707)
@@ -362,9 +362,6 @@
        }
 
        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 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/model_camera.cc   2008-06-29 00:35:54 UTC (rev 
6707)
@@ -16,7 +16,7 @@
 #include <sstream>
 #include <iomanip>
 
-Option StgModelCamera::ShowCamera( "Show Camera", true );
+Option StgModelCamera::ShowCamera( "Show Camera", "show_camera", "", true );
 
 //caclulate the corss product, and store results in the first vertex
 void cross( float& x1, float& y1, float& z1, float x2, float y2, float z2 )
@@ -184,6 +184,8 @@
        if( _frame_data == NULL || !ShowCamera )
                return;
        
+       // TODO - shift to global CS?
+
        float w_fov = _camera.horizFov();
        float h_fov = _camera.vertFov();
        
@@ -287,9 +289,6 @@
 //     glDrawElements( GL_QUADS, 4 * w * h, GL_UNSIGNED_SHORT, vertices_index 
);
 //     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 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/model_fiducial.cc 2008-06-29 00:35:54 UTC (rev 
6707)
@@ -299,7 +299,4 @@
 
                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 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/model_laser.cc    2008-06-29 00:35:54 UTC (rev 
6707)
@@ -17,23 +17,23 @@
 #include "stage_internal.hh"
 
 // DEFAULT PARAMETERS FOR LASER MODEL
-const bool StgModelLaser::DEFAULT_FILLED = true;
-const stg_watts_t StgModelLaser::DEFAULT_WATTS = 17.5;
-const stg_size_t StgModelLaser::DEFAULT_SIZE = {0.15, 0.15, 0.2 };
-const stg_meters_t StgModelLaser::DEFAULT_MINRANGE = 0.0;
-const stg_meters_t StgModelLaser::DEFAULT_MAXRANGE = 8.0;
-const stg_radians_t StgModelLaser::DEFAULT_FOV = M_PI;
-const unsigned int StgModelLaser::DEFAULT_SAMPLES = 180;
-const stg_msec_t StgModelLaser::DEFAULT_INTERVAL_MS = 100;
-const unsigned int StgModelLaser::DEFAULT_RESOLUTION = 1;
+static const bool DEFAULT_FILLED = true;
+static const stg_watts_t DEFAULT_WATTS = 17.5;
+static const stg_size_t DEFAULT_SIZE = {0.15, 0.15, 0.2 };
+static const stg_meters_t DEFAULT_MINRANGE = 0.0;
+static const stg_meters_t DEFAULT_MAXRANGE = 8.0;
+static const stg_radians_t DEFAULT_FOV = M_PI;
+static const unsigned int DEFAULT_SAMPLES = 180;
+static const stg_msec_t DEFAULT_INTERVAL_MS = 100;
+static const unsigned int DEFAULT_RESOLUTION = 1;
 
-const char StgModelLaser::DEFAULT_GEOM_COLOR[] = "blue";
-//const char BRIGHT_COLOR[] = "blue";
-//const char CFG_COLOR[] = "light steel blue";
-//const char COLOR[] = "steel blue";
-//const char FILL_COLOR[] = "powder blue";
+static const char DEFAULT_GEOM_COLOR[] = "blue";
+//static const char BRIGHT_COLOR[] = "blue";
+//static const char CFG_COLOR[] = "light steel blue";
+//static const char COLOR[] = "steel blue";
+//static const char FILL_COLOR[] = "powder blue";
 
-Option StgModelLaser::ShowLaserData( "Show Laser Data", true );
+Option StgModelLaser::ShowLaserData( "Show Laser Data", "show_laser", "", true 
);
 
 /**
   @ingroup model
@@ -83,12 +83,12 @@
                        id, typestr );
        
        // sensible laser defaults 
-       interval = StgModelLaser::DEFAULT_INTERVAL_MS * thousand;
+       interval = DEFAULT_INTERVAL_MS * thousand;
        laser_return = LaserVisible;
 
        stg_geom_t geom;
        memset( &geom, 0, sizeof(geom));
-       geom.size = StgModelLaser::DEFAULT_SIZE;
+       geom.size = DEFAULT_SIZE;
        SetGeom( geom );
 
        // set default color
@@ -237,7 +237,7 @@
        PRINT_DEBUG( "laser startup" );
 
        // start consuming power
-       SetWatts( StgModelLaser::DEFAULT_WATTS );
+       SetWatts( DEFAULT_WATTS );
 }
 
 void StgModelLaser::Shutdown( void )
@@ -305,12 +305,6 @@
        if( ! (samples && sample_count) )
                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
 
@@ -364,9 +358,4 @@
        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 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/model_ranger.cc   2008-06-29 00:35:54 UTC (rev 
6707)
@@ -313,12 +313,6 @@
        if( ! (samples && sensors && sensor_count) )
                return;
 
-       glPushMatrix();
-
-       // 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
@@ -379,11 +373,6 @@
        // restore state 
        glDepthMask( GL_TRUE );
        PopColor();
-       
-       glPopMatrix();
-       
-       // Call StgModel method to recurse on children
-       StgModel::DataVisualize();
 }
 
 

Added: code/stage/trunk/libstage/option.cc
===================================================================
--- code/stage/trunk/libstage/option.cc                         (rev 0)
+++ code/stage/trunk/libstage/option.cc 2008-06-29 00:35:54 UTC (rev 6707)
@@ -0,0 +1,43 @@
+#include "stage_internal.hh"
+
+using namespace Stg;
+
+void Option::Load( Worldfile* wf, int section )
+{
+  Set( (bool)wf->ReadInt(section, wf_token.c_str(), value ));
+}
+
+void Option::Save( Worldfile* wf, int section )
+{
+  wf->WriteInt(section, wf_token.c_str(), value );
+}
+
+void Option::CreateMenuItem( Fl_Menu_Bar* menu, std::string path )
+{
+  path = path + "/" + optName;
+  menu->add( path.c_str(), shortcut.c_str(), 
+                                (Fl_Callback*)ToggleCb, this, 
+                                FL_MENU_TOGGLE | (value ? FL_MENU_VALUE : 0 ) 
);
+  
+  // find the menu item we just created and store it for later access
+  menu_item = (Fl_Menu_Item*)menu->find_item( path.c_str() );
+}              
+
+void Option::ToggleCb( Fl_Menu_Bar* menubar, Option* opt ) 
+{
+  opt->Invert();
+}
+
+
+void Option::Invert()
+{
+  Set( !value );
+}
+
+void Option::Set( bool val )
+{
+  value = val;
+
+  if( menu_item )
+        value ? menu_item->set() : menu_item->clear();
+}

Modified: code/stage/trunk/libstage/option.hh
===================================================================
--- code/stage/trunk/libstage/option.hh 2008-06-27 23:52:07 UTC (rev 6706)
+++ code/stage/trunk/libstage/option.hh 2008-06-29 00:35:54 UTC (rev 6707)
@@ -2,7 +2,8 @@
  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
+ Author: Jeremy Asher, Richard Vaughan
+ SVN: $Id$
 */
 
 
@@ -10,32 +11,60 @@
 #define _OPTION_H_
 
 #include <string>
-#include <iostream>
+#include "worldfile.hh"
 
+#include <FL/Fl_Menu_Bar.H>
+#include <FL/Fl_Menu_Item.H>
+
 namespace Stg {
 
        class Option {
        private:
                friend bool compare( const Option* lhs, const Option* rhs );
-               
-               std::string optName;
-               bool value;
+
+         std::string optName;
+         bool value;
+         /** worldfile entry string for loading and saving this value */
+         std::string wf_token; 
+         std::string shortcut;
+         Fl_Menu_Item* menu_item;
+         
        public:
-               Option( std::string n, bool v ) : optName( n ), value( v ) { }
-               Option( const Option& o ) : optName( o.optName ), value( 
o.value ) { }
-               const std::string name() const { return optName; }
+         Option( std::string n, std::string tok, std::string key, bool v ) : 
+                optName( n ), 
+                wf_token( tok ), 
+                value( v ), 
+                shortcut( key ), 
+                menu_item( NULL )
+         { }
+         
+         Option( const Option& o ) : 
+                optName( o.optName ), 
+                wf_token( o.wf_token ), 
+                shortcut( o.shortcut ), 
+                value( o.value ) 
+         { }
+
+         const std::string name() const { return optName; }
                inline bool val() const { return value; }
                inline operator bool() { return val(); }
                inline bool operator<( const Option& rhs ) const
                        { return optName<rhs.optName; } 
-               void set( bool val ) { value = val; }
+         void Set( bool val );
+         void Invert();
+
+         // Comparator to dereference Option pointers and compare their strings
+         struct optComp {
+                inline bool operator()( const Option* lhs, const Option* rhs ) 
const
+                { return lhs->operator<(*rhs); } 
+         };
+         
+         static void ToggleCb( Fl_Menu_Bar* menubar, Option* opt );
+
+         void Load( Worldfile* wf, int section );
+         void Save( Worldfile* wf, int section );        
+         void CreateMenuItem( Fl_Menu_Bar* menu, std::string path );
        };
-       
-       // Comparator to dereference Option pointers and compare their strings
-       struct optComp {
-               inline bool operator()( const Option* lhs, const Option* rhs ) 
const
-                       { return lhs->operator<(*rhs); } 
-       };
 }
        
 #endif

Modified: code/stage/trunk/libstage/options_dlg.cc
===================================================================
--- code/stage/trunk/libstage/options_dlg.cc    2008-06-27 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/options_dlg.cc    2008-06-29 00:35:54 UTC (rev 
6707)
@@ -2,62 +2,63 @@
 #include <FL/Fl.H>
 
 namespace Stg {
-
-       OptionsDlg::OptionsDlg( int x, int y, int w, int h ) :
-       Fl_Window( x,y, w,h, "Options" ),
-       changedItem( NULL ),
-       showAll( NULL ),
-       status( NO_EVENT ),
-       hm( w/6 ) {
-               showAllCheck = new Fl_Check_Button( 0,0, w,boxH );
-               showAllCheck->callback( checkChanged, this );
-               showAllCheck->deactivate();
-               
-               scroll = new Fl_Scroll( 0,boxH+vm, w,h-boxH-btnH-3*vm );
-               scroll->type( Fl_Scroll::VERTICAL );
-               scroll->end();
-
-               
-               button = new Fl_Button( hm, h-btnH-vm, w-2*hm, btnH, "&Close" );
-               button->callback( closePress, this );
-               this->end();
-       }
-
+  
+  OptionsDlg::OptionsDlg( int x, int y, int w, int h ) :
+        Fl_Window( x,y, w,h, "Options" ),
+        changedItem( NULL ),
+        showAll( NULL ),
+        status( NO_EVENT ),
+        hm( w/6 ) 
+  {
+        showAllCheck = new Fl_Check_Button( 0,0, w,boxH );
+        showAllCheck->callback( checkChanged, this );
+        showAllCheck->deactivate();
+        
+        scroll = new Fl_Scroll( 0,boxH+vm, w,h-boxH-btnH-3*vm );
+        scroll->type( Fl_Scroll::VERTICAL );
+        scroll->end();
+        
+        
+        button = new Fl_Button( hm, h-btnH-vm, w-2*hm, btnH, "&Close" );
+        button->callback( closePress, this );
+        this->end();
+  }
+  
        OptionsDlg::~OptionsDlg() {
-               delete button;
-               delete scroll; // deletes members
-               delete showAllCheck;
+         delete button;
+         delete scroll; // deletes members
+         delete showAllCheck;
        }
-
-
-       void OptionsDlg::checkChanged( Fl_Widget* w, void* p ) {
-               Fl_Check_Button* check = static_cast<Fl_Check_Button*>( w );
-               OptionsDlg* oDlg = static_cast<OptionsDlg*>( p );
-               
-               if ( check == oDlg->showAllCheck && oDlg->showAll ) {
-                       oDlg->status = CHANGE_ALL;
-                       oDlg->showAll->set( check->value() );
+  
+  
+  void OptionsDlg::checkChanged( Fl_Widget* w, void* p ) {
+        Fl_Check_Button* check = static_cast<Fl_Check_Button*>( w );
+        OptionsDlg* oDlg = static_cast<OptionsDlg*>( p );
+        
+        if ( check == oDlg->showAllCheck && oDlg->showAll ) {
+               oDlg->status = CHANGE_ALL;
+                       oDlg->showAll->Set( check->value() );
                        oDlg->do_callback();
                        oDlg->status = NO_EVENT;
-               }
-               else {
-                       int item = oDlg->scroll->find( check );
-                       oDlg->options[ item ]->set( check->value() );
+        }
+        else {
+               int item = oDlg->scroll->find( check );
+               oDlg->options[ item ]->Set( check->value() );
                        oDlg->changedItem = oDlg->options[ item ];
                        oDlg->status = CHANGE;
                        oDlg->do_callback();
                        oDlg->changedItem = NULL;
                        oDlg->status = NO_EVENT;
-               }
-       }
-
-       void OptionsDlg::closePress( Fl_Widget* w, void* p ) {
-               OptionsDlg* oDlg = static_cast<OptionsDlg*>( p );
+        }
+  }
+  
+  void OptionsDlg::closePress( Fl_Widget* w, void* p ) {
+        OptionsDlg* oDlg = static_cast<OptionsDlg*>( p );
                
-               oDlg->status = CLOSE;
-               oDlg->do_callback();
-               oDlg->status = NO_EVENT;
-       }
+        oDlg->status = CLOSE;
+        oDlg->do_callback();
+        oDlg->status = NO_EVENT;
+  }
 
        int OptionsDlg::handle( int event ) {
        //      switch ( event ) {
@@ -88,7 +89,7 @@
                updateChecks();
        }
        
-       void OptionsDlg::setOptions( const std::set<Option*, optComp>& opts ) {
+  void OptionsDlg::setOptions( const std::set<Option*, Option::optComp>& opts 
) {
                options.clear();
                options.insert( options.begin(), opts.begin(), opts.end() );
                updateChecks();
@@ -100,4 +101,4 @@
                showAllCheck->value( opt->val() );
        }
 
-} // namespace Stg 
\ No newline at end of file
+} // namespace Stg 

Modified: code/stage/trunk/libstage/options_dlg.hh
===================================================================
--- code/stage/trunk/libstage/options_dlg.hh    2008-06-27 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/options_dlg.hh    2008-06-29 00:35:54 UTC (rev 
6707)
@@ -14,6 +14,8 @@
 
 namespace Stg {
 
+  //class Option;
+
        class OptionsDlg : protected Fl_Window {
        public:
                enum event_t { NO_EVENT, CHANGE, CHANGE_ALL, CLOSE };
@@ -46,7 +48,7 @@
                void hide() { Fl_Window::hide(); }
                
                void setOptions( const std::vector<Option*>& opts );
-               void setOptions( const std::set<Option*, optComp>& opts );
+         void setOptions( const std::set<Option*, Option::optComp>& opts );
                void clearOptions() { options.clear(); }
                void showAllOpt( Option* opt );
                const event_t event() const { return status; }

Modified: code/stage/trunk/libstage/stage.hh
===================================================================
--- code/stage/trunk/libstage/stage.hh  2008-06-27 23:52:07 UTC (rev 6706)
+++ code/stage/trunk/libstage/stage.hh  2008-06-29 00:35:54 UTC (rev 6707)
@@ -532,20 +532,20 @@
        /** Print human-readable velocity on stdout */
        void stg_print_velocity( stg_velocity_t* vel );
 
-       const uint32_t STG_SHOW_BLOCKS =     (1<<0);
-       const uint32_t STG_SHOW_DATA =       (1<<1);
-       const uint32_t STG_SHOW_GEOM =       (1<<2);
-       const uint32_t STG_SHOW_GRID =       (1<<3);
-       const uint32_t STG_SHOW_OCCUPANCY =  (1<<4);
-       const uint32_t STG_SHOW_TRAILS =     (1<<5);
-       const uint32_t STG_SHOW_FOLLOW =     (1<<6);
-       const uint32_t STG_SHOW_CLOCK =      (1<<7);
-       const uint32_t STG_SHOW_QUADTREE =   (1<<8);
-       const uint32_t STG_SHOW_ARROWS =     (1<<9);
-       const uint32_t STG_SHOW_FOOTPRINT =  (1<<10);
-       const uint32_t STG_SHOW_BLOCKS_2D =  (1<<10);
-       const uint32_t STG_SHOW_TRAILRISE =  (1<<11);
-       const uint32_t STG_SHOW_STATUS =     (1<<12);
+//     const uint32_t STG_SHOW_BLOCKS =     (1<<0);
+//     const uint32_t STG_SHOW_DATA =       (1<<1);
+//     const uint32_t STG_SHOW_GEOM =       (1<<2);
+//     const uint32_t STG_SHOW_GRID =       (1<<3);
+//     const uint32_t STG_SHOW_OCCUPANCY =  (1<<4);
+//     const uint32_t STG_SHOW_TRAILS =     (1<<5);
+//     const uint32_t STG_SHOW_FOLLOW =     (1<<6);
+//     const uint32_t STG_SHOW_CLOCK =      (1<<7);
+//     const uint32_t STG_SHOW_QUADTREE =   (1<<8);
+//     const uint32_t STG_SHOW_ARROWS =     (1<<9);
+//     const uint32_t STG_SHOW_FOOTPRINT =  (1<<10);
+//     const uint32_t STG_SHOW_BLOCKS_2D =  (1<<10);
+//     const uint32_t STG_SHOW_TRAILRISE =  (1<<11);
+//     const uint32_t STG_SHOW_STATUS =     (1<<12);
 
        // forward declare
        class StgWorld;
@@ -1182,36 +1182,7 @@
   uint32_t id;
 
 protected:
-  // basic model
-  static const bool DEFAULT_BLOBRETURN;
-  static const bool DEFAULT_BOUNDARY;
-  static const stg_color_t DEFAULT_COLOR;
-  static const stg_joules_t DEFAULT_ENERGY_CAPACITY;
-  static const bool DEFAULT_ENERGY_CHARGEENABLE;
-  static const stg_watts_t DEFAULT_ENERGY_GIVERATE;
-  static const stg_meters_t DEFAULT_ENERGY_PROBERANGE;
-  static const stg_watts_t DEFAULT_ENERGY_TRICKLERATE;
-  static const stg_meters_t DEFAULT_GEOM_SIZEX;
-  static const stg_meters_t DEFAULT_GEOM_SIZEY;
-  static const stg_meters_t DEFAULT_GEOM_SIZEZ;
-  static const bool DEFAULT_GRID;
-  static const bool DEFAULT_GRIPPERRETURN;
-  static const stg_laser_return_t DEFAULT_LASERRETURN;
-  static const stg_meters_t DEFAULT_MAP_RESOLUTION;
-  static const stg_movemask_t DEFAULT_MASK;
-  static const stg_kg_t DEFAULT_MASS;
-  static const bool DEFAULT_NOSE;
-  static const bool DEFAULT_OBSTACLERETURN;
-  static const bool DEFAULT_OUTLINE;
-  static const bool DEFAULT_RANGERRETURN;
-  
-  // speech bubble colors
-  static const stg_color_t BUBBLE_FILL;
-  static const stg_color_t BUBBLE_BORDER;
-  static const stg_color_t BUBBLE_TEXT; 
-
-  //const char* typestr;
-       stg_pose_t pose;
+  stg_pose_t pose;
        stg_velocity_t velocity;
        stg_watts_t watts; //< power consumed by this model
        stg_color_t color;
@@ -1402,11 +1373,13 @@
        /** OpenGL display list identifier */
        int displaylist;
 
-       /** Compile the display list for this model */
-       void BuildDisplayList( uint32_t flags );
-
+  /** Compile the display list for this model */
+  void BuildDisplayList();
+  
   stg_model_type_t type;
 
+  void DataVisualizeTree();
+
 public:
 
   static const char* typestr;
@@ -1709,7 +1682,7 @@
        StgModel* GetUnsubscribedModelOfType( stg_model_type_t type );
 
        // iff true, model may output some debugging visualizations and other 
info
-       bool debug;
+       //bool debug;
        
        const std::vector<Option*>& getOptions() const { return drawOptions; }
 };
@@ -1933,38 +1906,52 @@
                inline float getY() const { return _y; }
 };
 
+
 class StgCanvas : public Fl_Gl_Window
 {
-       friend class StgWorldGui; // allow access to private members
-       friend class StgModel;
+  friend class StgWorldGui; // allow access to private members
+  friend class StgModel;
+  
+private:
+  GlColorStack colorstack;
+  
+  StgOrthoCamera camera;
+  StgPerspectiveCamera perspective_camera;
+  bool use_perspective_camera;
+  
+  int startx, starty;
+  bool dragging;
+  bool rotating;
+  GList* selected_models; ///< a list of models that are currently
+  ///selected by the user
+  StgModel* last_selection; ///< the most recently selected model
+    ///(even if it is now unselected).
+    
+  stg_msec_t interval; // window refresh interval in ms
+  
+  GList* ray_list;
+  void RecordRay( double x1, double y1, double x2, double y2 );
+  void DrawRays();
+  void ClearRays();
+  void DrawGlobalGrid();
+  
+  Option 
+        showBlinken, 
+        showBlocks, 
+        showClock, 
+        showData, 
+        showFlags,
+        showFollow,
+        showFootprints, 
+        showGrid, 
+        showOccupancy, 
+        showTrailArrows, 
+        showTrailRise, 
+        showTrails, 
+        showTree;
+  
+public:
 
-       private:
-       GlColorStack colorstack;
-
-       StgOrthoCamera camera;
-       StgPerspectiveCamera perspective_camera;
-       bool use_perspective_camera;
-
-       int startx, starty;
-       bool dragging;
-       bool rotating;
-       GList* selected_models; ///< a list of models that are currently
-       ///selected by the user
-       StgModel* last_selection; ///< the most recently selected model
-       ///(even if it is now unselected).
-       uint32_t showflags;
-       stg_msec_t interval; // window refresh interval in ms
-
-       GList* ray_list;
-       void RecordRay( double x1, double y1, double x2, double y2 );
-       void DrawRays();
-       void ClearRays();
-       void DrawGlobalGrid();
-       
-       Option ShowFlags;
-
-       public:
-
        StgCanvas( StgWorldGui* world, int x, int y, int W,int H);
        ~StgCanvas();
 
@@ -1972,7 +1959,9 @@
        StgWorldGui* world;
 
   void Screenshot();
-
+  
+  void CreateMenuItems( Fl_Menu_Bar* menu, std::string path );
+  
        void FixViewport(int W,int H);
        void DrawFloor(); //simpler floor compared to grid
        void DrawBlocks();
@@ -1996,11 +1985,10 @@
 
        void InvertView( uint32_t invertflags );
 
-       uint32_t GetShowFlags(){ return showflags; }
-
-       void SetShowFlags( uint32_t flags ){ showflags = flags; }
-
        static void TimerCallback( StgCanvas* canvas );
+  
+  void Load( Worldfile* wf, int section );
+  void Save( Worldfile* wf, int section );
 };
 
 
@@ -2011,7 +1999,7 @@
 {
   friend class StgCanvas;
   friend class StgModelCamera;
-  
+
 private:
   bool paused; ///< the world only updates when this is false
   //int wf_section;
@@ -2068,15 +2056,13 @@
        
        StgCanvas* GetCanvas( void ) { return canvas; }
 
-
+private:
        // static callback functions
-       static void windowCb( Fl_Widget* w, void* p );
-       
+       static void windowCb( Fl_Widget* w, void* p );  
        static void fileLoadCb( Fl_Widget* w, void* p );
        static void fileSaveCb( Fl_Widget* w, void* p );
        static void fileSaveAsCb( Fl_Widget* w, void* p );
        static void fileExitCb( Fl_Widget* w, void* p );
-       static void viewToggleCb( Fl_Widget* w, void* p );
        static void viewOptionsCb( Fl_Widget* w, void* p );
        static void optionsDlgCb( Fl_Widget* w, void* p );
        static void helpAboutCb( Fl_Widget* w, void* p );
@@ -2210,18 +2196,6 @@
 class StgModelLaser : public StgModel
 {
 private:
-  // DEFAULT PARAMETERS FOR LASER MODEL
-  static const bool DEFAULT_FILLED;
-  static const stg_watts_t DEFAULT_WATTS; 
-  static const stg_size_t DEFAULT_SIZE;
-  static const stg_meters_t DEFAULT_MINRANGE;
-  static const stg_meters_t DEFAULT_MAXRANGE;
-  static const stg_radians_t DEFAULT_FOV;
-  static const unsigned int DEFAULT_SAMPLES;
-  static const stg_msec_t DEFAULT_INTERVAL_MS;
-  static const unsigned int DEFAULT_RESOLUTION;
-  static const char DEFAULT_GEOM_COLOR[];
-
   int dl_debug_laser;
   
   stg_laser_sample_t* samples;

Modified: code/stage/trunk/libstage/worldfile.hh
===================================================================
--- code/stage/trunk/libstage/worldfile.hh      2008-06-27 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/worldfile.hh      2008-06-29 00:35:54 UTC (rev 
6707)
@@ -32,6 +32,10 @@
 #include <stdio.h> // for FILE ops
 #include <glib.h>
 
+//#include "stage.hh"
+
+namespace Stg {
+
   // Private property class
 struct CProperty
   {
@@ -60,7 +64,7 @@
 // interface.  Global settings go in entity 0; every other entity
 // refers to a specific entity.  Parent/child relationships are
 // encoded in the form of entity/subentity relationships.
-class Stg::Worldfile
+class Worldfile
 {
   // Standard constructors/destructors
 public: Worldfile();
@@ -355,4 +359,6 @@
   private: double unit_angle;
 };
 
+};
+
 #endif

Modified: code/stage/trunk/libstage/worldgui.cc
===================================================================
--- code/stage/trunk/libstage/worldgui.cc       2008-06-27 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/libstage/worldgui.cc       2008-06-29 00:35:54 UTC (rev 
6707)
@@ -109,32 +109,14 @@
 
 #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_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
 #ifndef PACKAGE_STRING
 #define PACKAGE_STRING "Stage-3.dev"
 #endif
 
-
-
-
-StgWorldGui::StgWorldGui(int W,int H,const char* L) : Fl_Window(W,H,L),
-ShowAll( "Visualize all models", true )
+       StgWorldGui::StgWorldGui(int W,int H,const char* L) : 
+       Fl_Window(W,H,L),
+       ShowAll( "Visualize all models", "show_vis", "", true )
 {
        //size_range( 100,100 ); // set minimum window size
        oDlg = NULL;
@@ -158,40 +140,16 @@
        mbar->add( "File/&Load World...", FL_CTRL + 'l', 
StgWorldGui::fileLoadCb, this, FL_MENU_DIVIDER );
        mbar->add( "File/&Save World", FL_CTRL + 's', StgWorldGui::fileSaveCb, 
this );
        mbar->add( "File/Save World &As...", FL_CTRL + FL_SHIFT + 's', 
StgWorldGui::fileSaveAsCb, this, FL_MENU_DIVIDER );
+
+       mbar->add( "File/Screenshots", 0,0,0, FL_SUBMENU );
+       //mbar->add( "File/Screenshots/
+
        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, 
-                       FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_DATA ? 
FL_MENU_VALUE : 0 ));
-       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_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, 'o', StgWorldGui::viewToggleCb, 
canvas, 
-                       FL_MENU_TOGGLE| (canvas->showflags & STG_SHOW_OCCUPANCY 
? FL_MENU_VALUE : 0 ));
-       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 ));
-       mbar->add( MITEM_VIEW_CLOCK,    'c', StgWorldGui::viewToggleCb, canvas, 
-                         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_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_DIVIDER);
-       mbar->add( "View/Additional options...", FL_CTRL + 'o', 
StgWorldGui::viewOptionsCb, this );
+       mbar->add( "View/Filter data...", FL_SHIFT + 'd', 
StgWorldGui::viewOptionsCb, this );
+       canvas->CreateMenuItems( mbar, "View" );
 
-
        mbar->add( "&Help", 0, 0, 0, FL_SUBMENU );
        mbar->add( "Help/&About Stage...", 0, StgWorldGui::helpAboutCb, this );
        //mbar->add( "Help/HTML Documentation", FL_CTRL + 'g', (Fl_Callback 
*)dummy_cb );
@@ -209,8 +167,6 @@
        delete canvas;
 }
 
-
-
 void StgWorldGui::Load( const char* filename )
 {
        PRINT_DEBUG1( "%s.Load()", token );
@@ -242,61 +198,10 @@
        //larger than this size.
        size( width,height );
 
-       float x = wf->ReadTupleFloat(window_section, "center", 0, 0 );
-       float y = wf->ReadTupleFloat(window_section, "center", 1, 0 );
-       canvas->camera.setPose( x, y );
-
-       canvas->camera.setPitch( wf->ReadTupleFloat( window_section, "rotate", 
0, 0 ) );
-       canvas->camera.setYaw( wf->ReadTupleFloat( window_section, "rotate", 1, 
0 ) );
-       canvas->camera.setScale( wf->ReadFloat(window_section, "scale", 
canvas->camera.getScale() ) );
-       canvas->interval = wf->ReadInt(window_section, "interval", 
canvas->interval );
-
-       // set the canvas visibilty flags   
-       uint32_t flags = canvas->GetShowFlags();
-       uint32_t grid = wf->ReadInt(window_section, "show_grid", flags & 
STG_SHOW_GRID ) ? STG_SHOW_GRID : 0;
-       uint32_t data = wf->ReadInt(window_section, "show_data", flags & 
STG_SHOW_DATA ) ? STG_SHOW_DATA : 0;
-       uint32_t follow = wf->ReadInt(window_section, "show_follow", flags & 
STG_SHOW_FOLLOW ) ? STG_SHOW_FOLLOW : 0;
-       uint32_t blocks = wf->ReadInt(window_section, "show_blocks", flags & 
STG_SHOW_BLOCKS ) ? STG_SHOW_BLOCKS : 0;
-       uint32_t quadtree = wf->ReadInt(window_section, "show_tree", flags & 
STG_SHOW_QUADTREE ) ? STG_SHOW_QUADTREE : 0;
-       uint32_t clock = wf->ReadInt(window_section, "show_clock", flags & 
STG_SHOW_CLOCK ) ? STG_SHOW_CLOCK : 0;
-       uint32_t trails = wf->ReadInt(window_section, "show_trails", flags & 
STG_SHOW_TRAILS ) ? STG_SHOW_TRAILS : 0;
-       uint32_t trailsrising = wf->ReadInt(window_section, 
"show_trails_rising", flags & STG_SHOW_TRAILRISE ) ? STG_SHOW_TRAILRISE : 0;
-       uint32_t arrows = wf->ReadInt(window_section, "show_arrows", flags & 
STG_SHOW_ARROWS ) ? STG_SHOW_ARROWS : 0;
-       uint32_t footprints = wf->ReadInt(window_section, "show_footprints", 
flags & STG_SHOW_FOOTPRINT ) ? STG_SHOW_FOOTPRINT : 0;
-       uint32_t status = wf->ReadInt(window_section, "show_status", flags & 
STG_SHOW_STATUS ) ? STG_SHOW_STATUS : 0;
-
-       canvas->SetShowFlags( grid | data | follow | blocks | quadtree | clock
-                       | trails | arrows | footprints | trailsrising | status 
);
-       canvas->invalidate(); // we probably changed something
-
-       // fix the GUI menu checkboxes to match
-       flags = canvas->GetShowFlags();
-
-       Fl_Menu_Item* item = NULL;
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_DATA );
-       (flags & STG_SHOW_DATA) ? item->check() : item->clear();
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_GRID );
-       (flags & STG_SHOW_GRID) ? item->check() : item->clear();
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_BLOCKS );
-       (flags & STG_SHOW_BLOCKS) ? item->check() : item->clear();
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_FOLLOW );
-       (flags & STG_SHOW_FOLLOW) ? item->check() : item->clear();
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_OCCUPANCY );
-       (flags & STG_SHOW_OCCUPANCY) ? item->check() : item->clear();
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_QUADTREE );
-       (flags & STG_SHOW_QUADTREE) ? item->check() : item->clear();
-
-       item = (Fl_Menu_Item*)mbar->find_item( MITEM_VIEW_STATUS );
-       (flags & STG_SHOW_STATUS) ? item->check() : item->clear();
-
+       // configure the canvas
+       canvas->Load(  wf, window_section );
+       
        updateOptions();
-       // TODO - per model visualizations load
 }
 
 void StgWorldGui::UnLoad() 
@@ -318,23 +223,8 @@
          {
                 wf->WriteTupleFloat( window_section, "size", 0, w() );
                 wf->WriteTupleFloat( window_section, "size", 1, h() );
-                
-                wf->WriteFloat( window_section, "scale", 
canvas->camera.getScale() );
-                
-                wf->WriteTupleFloat( window_section, "center", 0, 
canvas->camera.getX() );
-                wf->WriteTupleFloat( window_section, "center", 1, 
canvas->camera.getY() );
-                
-                wf->WriteTupleFloat( window_section, "rotate", 0, 
canvas->camera.getPitch()  );
-                wf->WriteTupleFloat( window_section, "rotate", 1, 
canvas->camera.getYaw()  );
-                
-                uint32_t flags = canvas->GetShowFlags();
-                wf->WriteInt( window_section, "show_blocks", flags & 
STG_SHOW_BLOCKS );
-                wf->WriteInt( window_section, "show_grid", flags & 
STG_SHOW_GRID );
-                wf->WriteInt( window_section, "show_follow", flags & 
STG_SHOW_FOLLOW );
-                wf->WriteInt( window_section, "show_data", flags & 
STG_SHOW_DATA );
-                wf->WriteInt( window_section, "show_occupancy", flags & 
STG_SHOW_OCCUPANCY );
-                wf->WriteInt( window_section, "show_tree", flags & 
STG_SHOW_QUADTREE );
-                wf->WriteInt( window_section, "show_clock", flags & 
STG_SHOW_CLOCK );
+                                
+                canvas->Save( wf, window_section );
 
                 // TODO - per model visualizations save 
          }
@@ -522,36 +412,7 @@
        }
 }
 
-void StgWorldGui::viewToggleCb( Fl_Widget* w, void* p ) 
-{
-       Fl_Menu_Bar* menubar = static_cast<Fl_Menu_Bar*>( w );
-       StgCanvas* canvas = static_cast<StgCanvas*>( p );
 
-       char picked[128];
-       menubar->item_pathname(picked, sizeof(picked)-1);
-
-       //printf("CALLBACK: You picked '%s'\n", picked);
-
-       // this is slow and a little ugly, but it's the least hacky approach I 
think
-       if( strcmp(picked, MITEM_VIEW_DATA ) == 0 ) canvas->InvertView( 
STG_SHOW_DATA );
-       else if( strcmp(picked, MITEM_VIEW_BLOCKS ) == 0 ) canvas->InvertView( 
STG_SHOW_BLOCKS );
-       else if( strcmp(picked, MITEM_VIEW_GRID ) == 0 ) canvas->InvertView( 
STG_SHOW_GRID );
-       else if( strcmp(picked, MITEM_VIEW_FOLLOW ) == 0 ) canvas->InvertView( 
STG_SHOW_FOLLOW );
-       else if( strcmp(picked, MITEM_VIEW_QUADTREE ) == 0 ) 
canvas->InvertView( STG_SHOW_QUADTREE );
-       else if( strcmp(picked, MITEM_VIEW_OCCUPANCY ) == 0 ) 
canvas->InvertView( STG_SHOW_OCCUPANCY );
-       else if( strcmp(picked, MITEM_VIEW_CLOCK ) == 0 ) canvas->InvertView( 
STG_SHOW_CLOCK );
-       else if( strcmp(picked, MITEM_VIEW_FOOTPRINTS ) == 0 ) 
canvas->InvertView( STG_SHOW_FOOTPRINT );
-       else if( strcmp(picked, MITEM_VIEW_ARROWS ) == 0 ) canvas->InvertView( 
STG_SHOW_ARROWS );
-       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 );
-
-       //printf( "value: %d\n", item->value() );
-}
-
 void StgWorldGui::viewOptionsCb( Fl_Widget* w, void* p ) {
        StgWorldGui* worldGui = static_cast<StgWorldGui*>( p );
 
@@ -742,7 +603,7 @@
 }
 
 void StgWorldGui::updateOptions() {
-       std::set<Option*, optComp> options;
+  std::set<Option*, Option::optComp> options;
        std::vector<Option*> modOpts;
        for( GList* it=update_list; it; it=it->next ) {
                modOpts = ((StgModel*)it->data)->getOptions();

Modified: code/stage/trunk/worlds/everything.world
===================================================================
--- code/stage/trunk/worlds/everything.world    2008-06-27 23:52:07 UTC (rev 
6706)
+++ code/stage/trunk/worlds/everything.world    2008-06-29 00:35:54 UTC (rev 
6707)
@@ -54,16 +54,18 @@
 #
 define trickedoutpioneer pioneer2dx
 (
-  sicklaser(  
+  sicklaser( alwayson 1 
     pose [0.030 0.000 0.000 ]
     fiducial( range_max 8 range_max_id 5 ) 
 
-      blobfinder( 
+      blobfinder( alwayson 1
         channel_count 6 
         channels [ "red" "blue" "green" "cyan" "yellow" "magenta" ]  
     )
   )
 
+  camera( alwayson 1 )
+
   fiducial_return 17
   gripper_return 0
 

Modified: code/stage/trunk/worlds/fasr.world
===================================================================
--- code/stage/trunk/worlds/fasr.world  2008-06-27 23:52:07 UTC (rev 6706)
+++ code/stage/trunk/worlds/fasr.world  2008-06-29 00:35:54 UTC (rev 6707)
@@ -61,7 +61,7 @@
 #camera( pose [ 0.000 0.000 0.000 ] width 100 height 100 horizfov 70 vertfov 
40 yaw 0 )
  ctrl "fasr"
 
-  # say "Autolab"
+  say "Autolab"
 )
 
 


This was sent by the SourceForge.net collaborative development platform, the 
world's largest Open Source development site.

-------------------------------------------------------------------------
Check out the new SourceForge.net Marketplace.
It's the best place to buy or sell services for
just about anything Open Source.
http://sourceforge.net/services/buy/index.php
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to