Revision: 7189
          http://playerstage.svn.sourceforge.net/playerstage/?rev=7189&view=rev
Author:   rtv
Date:     2008-12-05 22:31:14 +0000 (Fri, 05 Dec 2008)

Log Message:
-----------
code tidying - eliminated all -Wall warnings

Modified Paths:
--------------
    code/stage/trunk/examples/ctrl/fasr.cc
    code/stage/trunk/libstage/block.cc
    code/stage/trunk/libstage/blockgroup.cc
    code/stage/trunk/libstage/canvas.cc
    code/stage/trunk/libstage/model.cc
    code/stage/trunk/libstage/model_laser.cc
    code/stage/trunk/libstage/model_load.cc
    code/stage/trunk/libstage/region.cc
    code/stage/trunk/libstage/stage.cc
    code/stage/trunk/libstage/stage.hh
    code/stage/trunk/libstage/world.cc
    code/stage/trunk/libstage/worldgui.cc
    code/stage/trunk/worlds/benchmark/expand.cc
    code/stage/trunk/worlds/fasr.world
    code/stage/trunk/worlds/simple.world
    code/stage/trunk/worlds/walle.inc

Modified: code/stage/trunk/examples/ctrl/fasr.cc
===================================================================
--- code/stage/trunk/examples/ctrl/fasr.cc      2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/examples/ctrl/fasr.cc      2008-12-05 22:31:14 UTC (rev 
7189)
@@ -61,7 +61,7 @@
 
   robot->ranger = (StgModelRanger*)mod->GetModel( "ranger:0" );
   assert( robot->ranger );
-  robot->ranger->Subscribe();
+  //robot->ranger->Subscribe();
 
 
   robot->avoidcount = 0;

Modified: code/stage/trunk/libstage/block.cc
===================================================================
--- code/stage/trunk/libstage/block.cc  2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/block.cc  2008-12-05 22:31:14 UTC (rev 7189)
@@ -39,8 +39,8 @@
                                                        Worldfile* wf, 
                                                        int entity) 
   : mod( mod ),
+        pt_count(0), 
         pts(NULL), 
-        pt_count(0), 
         color(0),
         inherit_color(true),
         rendered_cells( g_ptr_array_sized_new(32) ), 
@@ -86,7 +86,7 @@
   GenerateCandidateCells();
   
   // for every cell we may be rendered into
-  for( int i=0; i<candidate_cells->len; i++ )
+  for( unsigned int i=0; i<candidate_cells->len; i++ )
         {
                Cell* cell = (Cell*)g_ptr_array_index(candidate_cells, i);
                
@@ -178,17 +178,21 @@
   // add local offset
   gpose = pose_sum( gpose, mod->geom.pose );
 
+  stg_size_t bgsize = mod->blockgroup.GetSize();
+  stg_point3_t bgoffset = mod->blockgroup.GetOffset();
+
   stg_point3_t scale;
-  scale.x = mod->geom.size.x / mod->blockgroup.size.x;
-  scale.y = mod->geom.size.y / mod->blockgroup.size.y;
-  scale.z = mod->geom.size.z / mod->blockgroup.size.z;
+  scale.x = mod->geom.size.x / bgsize.x;
+  scale.y = mod->geom.size.y / bgsize.y;
+  scale.z = mod->geom.size.z / bgsize.z;
 
+
   g_ptr_array_set_size( candidate_cells, 0 );
   
   // compute the global location of the first point
-  stg_pose_t local( (pts[0].x - mod->blockgroup.offset.x) * scale.x ,
-                                                 (pts[0].y - 
mod->blockgroup.offset.y) * scale.y, 
-                                                 -mod->blockgroup.offset.z, 
+  stg_pose_t local( (pts[0].x - bgoffset.x) * scale.x ,
+                                                 (pts[0].y - bgoffset.y) * 
scale.y, 
+                                                 -bgoffset.z, 
                                                  0 );
 
   stg_pose_t first_gpose, last_gpose;
@@ -199,11 +203,11 @@
   global_z.max = (scale.z * local_z.max) + last_gpose.z;               
   
   // now loop from the the second to the last
-  for( int p=1; p<pt_count; p++ )
+  for( unsigned int p=1; p<pt_count; p++ )
         {
-               stg_pose_t local( (pts[p].x - mod->blockgroup.offset.x) * 
scale.x ,
-                                                               (pts[p].y - 
mod->blockgroup.offset.y) * scale.y, 
-                                                               
-mod->blockgroup.offset.z, 
+               stg_pose_t local( (pts[p].x - bgoffset.x) * scale.x ,
+                                                               (pts[p].y - 
bgoffset.y) * scale.y, 
+                                                               -bgoffset.z, 
                                                                0 );            
                
                stg_pose_t gpose2 = pose_sum( gpose, local );
@@ -231,7 +235,7 @@
   // draw the top of the block - a polygon at the highest vertical
   // extent
   glBegin( GL_POLYGON);
-  for( int i=0; i<pt_count; i++ )
+  for( unsigned int i=0; i<pt_count; i++ )
         glVertex3f( pts[i].x, pts[i].y, local_z.max );
   glEnd();
 }       
@@ -311,8 +315,7 @@
   //    pt_count );
   
   char key[128];  
-  int p;
-  for( p=0; p<pt_count; p++ )        {
+  for( unsigned int p=0; p<pt_count; p++ )           {
         snprintf(key, sizeof(key), "point[%d]", p );
         
         pts[p].x = wf->ReadTupleLength(entity, key, 0, 0);

Modified: code/stage/trunk/libstage/blockgroup.cc
===================================================================
--- code/stage/trunk/libstage/blockgroup.cc     2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/libstage/blockgroup.cc     2008-12-05 22:31:14 UTC (rev 
7189)
@@ -7,9 +7,13 @@
 using namespace Stg;
 
 BlockGroup::BlockGroup() 
-  : blocks(NULL), 
+  : displaylist(0),
+        blocks(NULL), 
         count(0), 
-        displaylist(0)
+        minx(0),
+        maxx(0),
+        miny(0),
+        maxy(0)
 { /* empty */ }
 
 BlockGroup::~BlockGroup()
@@ -51,7 +55,7 @@
   StgModel* hitmod = NULL;
   
   for( GList* it=blocks; it; it = it->next )
-        if( hitmod = ((StgBlock*)it->data)->TestCollision())
+        if( (hitmod = ((StgBlock*)it->data)->TestCollision()))
                break; // bail on the earliest collision
   
   //printf( "blockgroup %p test collision done.\n", this );
@@ -65,7 +69,7 @@
 void BlockGroup::CalcSize()
 {  
   // assuming the blocks currently fit in a square +/- one billion units
-  double minx, miny, maxx, maxy, minz, maxz;
+  //double minx, miny, maxx, maxy, minz, maxz;
   minx = miny =  billion;
   maxx = maxy = -billion;
   
@@ -152,8 +156,11 @@
   //printf( "display list for model %s\n", mod->token );
 
   if( displaylist == 0 )
-        displaylist = glGenLists(1);
-  
+        {
+               displaylist = glGenLists(1);
+               CalcSize();
+        }
+
   glNewList( displaylist, GL_COMPILE );        
     
 
@@ -271,8 +278,8 @@
   if( rects && (rect_count > 0) )
         {
                // shift the origin from bottom-left to center of the image
-               double dx = width/2.0;
-               double dy = height/2.0;
+               //double dx = width/2.0;
+               //double dy = height/2.0;
                
                //puts( "loading rects" );
                for( unsigned int r=0; r<rect_count; r++ )
@@ -284,14 +291,23 @@
                         double w = rects[r].size.x;
                         double h = rects[r].size.y;
                         
-                        pts[0].x = x - dx;
-                        pts[0].y = y - dy;
-                        pts[1].x = x + w - dx;
-                        pts[1].y = y -dy;
-                        pts[2].x = x + w -dx;
-                        pts[2].y = y + h -dy;
-                        pts[3].x = x - dx;
-                        pts[3].y = y + h -dy;                                  
                 
+//                      pts[0].x = x - dx;
+//                      pts[0].y = y - dy;
+//                      pts[1].x = x + w - dx;
+//                      pts[1].y = y -dy;
+//                      pts[2].x = x + w -dx;
+//                      pts[2].y = y + h -dy;
+//                      pts[3].x = x - dx;
+//                      pts[3].y = y + h -dy;                                  
                 
+
+                        pts[0].x = x;
+                        pts[0].y = y;
+                        pts[1].x = x + w;
+                        pts[1].y = y;
+                        pts[2].x = x + w;
+                        pts[2].y = y + h;
+                        pts[3].x = x;
+                        pts[3].y = y + h;                                      
                 
                         
                         // TODO fix this
                         stg_color_t col = stg_color_pack( 1.0, 0,0,1.0 ); 

Modified: code/stage/trunk/libstage/canvas.cc
===================================================================
--- code/stage/trunk/libstage/canvas.cc 2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/canvas.cc 2008-12-05 22:31:14 UTC (rev 7189)
@@ -49,10 +49,15 @@
                                                         int x, int y, 
                                                         int width, int height) 
:
   Fl_Gl_Window( x, y, width, height ),
+  wf( NULL ),
+  startx( -1 ),
+  starty( -1 ),
+  selected_models( NULL ),
+  last_selection( NULL ),
+  interval(  50 ), //msec between redraws
   // initialize Option objects
   showBlinken( "Blinkenlights", "show_blinkenlights", "", true ),
   showBlocks( "Blocks", "show_blocks", "b", true  ),
-  showBBoxes( "Debug/Bounding boxes", "show_boundingboxes", "^b", false  ),
   showClock( "Clock", "show_clock", "c", true ),
   showData( "Data", "show_data", "d", false ),
   showFlags( "Flags", "show_flags", "l",  true ),
@@ -66,18 +71,13 @@
   showTrailRise( "Trails/Rising blocks", "show_trailrise", "^r", false ),
   showTrails( "Trails/Fast", "show_trailfast", "^f", false ),
   showTree( "Debug/Tree", "show_tree", "^t", false ),
+  showBBoxes( "Debug/Bounding boxes", "show_boundingboxes", "^b", false  ),
   showBlur( "Trails/Blur", "show_trailblur", "^d", false ),
   pCamOn( "Perspective camera", "pcam_on", "r", false ),
   visualizeAll( "Visualize All", "vis_all", "^v", true ),
-  // and the rest
-  world( world ),
-  selected_models( NULL ),
-  last_selection( NULL ),
-  wf( NULL ),
-  startx( -1 ),
-  starty( -1 ),
-  interval(  50 ), //msec between redraws
-  graphics( true )
+  // and the rest 
+  graphics( true ),
+  world( world )
 {
   end();
   
@@ -524,6 +524,27 @@
                         }
                         redraw();
                         break;                 
+
+                 case '[': // slow down
+                        if( world->interval_real == 0 )
+                               world->interval_real = 10;
+                        else
+                               {
+                                 world->interval_real *= 1.2;
+                               }
+                        break; // need the parens above
+
+                 case ']': // speed up
+                        if( world->interval_real == 0 )
+                               putchar( 7 ); // bell!
+                        else
+                               {
+                                 world->interval_real *= 0.8;
+                                 if( world->interval_real < 10 )
+                                        world->interval_real = 0;
+                               }
+                        break;
+
                  case FL_Left:
                         if( pCamOn == false ) { camera.move( -10, 0 ); } 
                         else { perspective_camera.strafe( -0.5 ); } break;

Modified: code/stage/trunk/libstage/model.cc
===================================================================
--- code/stage/trunk/libstage/model.cc  2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/model.cc  2008-12-05 22:31:14 UTC (rev 7189)
@@ -117,29 +117,7 @@
 //#define DEBUG 0
 #include "stage_internal.hh"
 #include "texture_manager.hh"
-//#include <limits.h> 
 
-
-//static const members
-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 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_BLOBRETURN = true;
-static const bool DEFAULT_OUTLINE = true;
-static const bool DEFAULT_RANGERRETURN = true;
-
 // speech bubble colors
 static const stg_color_t BUBBLE_FILL = 0xFFC8C8FF; // light blue/grey
 static const stg_color_t BUBBLE_BORDER = 0xFF000000; // black
@@ -154,47 +132,59 @@
 StgModel::StgModel( StgWorld* world,
                                                  StgModel* parent,
                                                  const stg_model_type_t type )
-  : StgAncestor(), 
-        world(world),
-        parent(parent),
-        type(type),
-    id( StgModel::count++ ),
-        trail( g_array_new( false, false, sizeof(stg_trail_item_t) )),
+  : StgAncestor(),      
+        blinkenlights( g_ptr_array_new() ),
+        blob_return(true),
+        blockgroup(),
         blocks_dl(0),
+        boundary(false),
+        callbacks( g_hash_table_new( g_int_hash, g_int_equal ) ),
+        color( 0xFFFF0000 ), // red
         data_fresh(false),
         disabled(false),
+        fiducial_key(0),
+        fiducial_return(0),
+        flag_list(NULL),
+        geom(),
+        gripper_return(false),
+        gui_grid(false),
+        gui_mask( parent ? 0 : (STG_MOVE_TRANS | STG_MOVE_ROT) ),
+        gui_nose(false),
+        gui_outline(false),
+        has_default_block( true ),
+        hook_load(0),
+        hook_save(0),
+        hook_shutdown(0),
+        hook_startup(0),
+        hook_update(0),
+    id( StgModel::count++ ),
+        initfunc(NULL),
+        interval((stg_usec_t)1e4), // 10msec
+        laser_return(LaserVisible),
+        last_update(0),
+        map_caches_are_invalid( true ),
+        map_resolution(0.1),
+        mass(0),
+        obstacle_return(true),
+        on_update_list( false ),
+        on_velocity_list( false ),
+        parent(parent),
+        pose(),
+        props(NULL),
+        ranger_return(true),
         rebuild_displaylist(true),
         say_string(NULL),
+        stall(false),   
         subs(0),
+        thread_safe( false ),
+        trail( g_array_new( false, false, sizeof(stg_trail_item_t) )),
+        type(type),    
         used(false),
-        stall(false),   
-        obstacle_return(DEFAULT_OBSTACLERETURN),
-        ranger_return(DEFAULT_RANGERRETURN),
-        blob_return(DEFAULT_BLOBRETURN),
-        laser_return(DEFAULT_LASERRETURN),
-        gripper_return(DEFAULT_GRIPPERRETURN),
-        fiducial_return(0),
-        fiducial_key(0),
-        boundary(DEFAULT_BOUNDARY),
-        color(DEFAULT_COLOR),
-        map_resolution(DEFAULT_MAP_RESOLUTION),
-        gui_nose(DEFAULT_NOSE),
-        gui_grid(DEFAULT_GRID),
-        gui_outline(DEFAULT_OUTLINE),
-        gui_mask( parent ? 0 : DEFAULT_MASK),
-        callbacks( g_hash_table_new( g_int_hash, g_int_equal ) ),
-        flag_list(NULL),
-        blinkenlights( g_ptr_array_new() ),
-        last_update(0),
-        interval((stg_usec_t)1e4), // 10msec
-        initfunc(NULL),
+        velocity(),
+        watts(0),
         wf(NULL),
-        on_velocity_list( false ),
-        on_update_list( false ),
         wf_entity(0),
-        has_default_block( true ),
-        map_caches_are_invalid( true ),
-        thread_safe( false )
+        world(world)
 {
   assert( modelsbyid );
   assert( world );
@@ -678,7 +668,7 @@
 
   StartUpdating();
 
-  CallCallbacks( &startup_hook );
+  CallCallbacks( &hook_startup );
 }
 
 void StgModel::Shutdown( void )
@@ -687,7 +677,7 @@
 
   StopUpdating();
 
-  CallCallbacks( &shutdown_hook );
+  CallCallbacks( &hook_shutdown );
 }
 
 void StgModel::UpdateIfDue( void )
@@ -706,7 +696,7 @@
   //   printf( "[%llu] %s update (%d subs)\n", 
   //                    this->world->sim_time, this->token, this->subs );
 
-  CallCallbacks( &update_hook );
+  CallCallbacks( &hook_update );
   last_update = world->sim_time;
 }
 

Modified: code/stage/trunk/libstage/model_laser.cc
===================================================================
--- code/stage/trunk/libstage/model_laser.cc    2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/libstage/model_laser.cc    2008-12-05 22:31:14 UTC (rev 
7189)
@@ -75,13 +75,14 @@
   StgModelLaser::StgModelLaser( StgWorld* world, 
                                                                                
  StgModel* parent )
   : StgModel( world, parent, MODEL_TYPE_LASER ),
+       data_dl(0),
+       data_dirty( true ),
+       samples( NULL ),        // don't allocate sample buffer memory until 
Update() is called
+       sample_count( DEFAULT_SAMPLES ),
        range_min( DEFAULT_MINRANGE ),
        range_max( DEFAULT_MAXRANGE ),
        fov( DEFAULT_FOV ),
-       sample_count( DEFAULT_SAMPLES ),
-       resolution( DEFAULT_RESOLUTION ),
-       data_dirty( true ),
-       samples( NULL )         // don't allocate sample buffer memory until 
Update() is called
+       resolution( DEFAULT_RESOLUTION )
 {
   
   PRINT_DEBUG2( "Constructing StgModelLaser %d (%s)\n", 
@@ -334,41 +335,42 @@
       
       pts[0] = 0.0;
       pts[1] = 0.0;
-
-      if( showLaserData )
-                 {      
-                        PushColor( 0, 0, 1, 0.5 );
+               
+               PushColor( 0, 0, 1, 0.5 );
+               glDepthMask( GL_FALSE );
+               glPointSize( 2 );
+               
+               for( unsigned int s=0; s<sample_count; s++ )
+                 {
+                        double ray_angle = (s * (fov / (sample_count-1))) - 
fov/2.0;
+                        pts[2*s+2] = (float)(samples[s].range * cos(ray_angle) 
);
+                        pts[2*s+3] = (float)(samples[s].range * sin(ray_angle) 
);
                         
-                        for( unsigned int s=0; s<sample_count; s++ )
+                        // if the sample is unusually bright, draw a little 
blob
+                        if( showLaserData && (samples[s].reflectance > 0) )
                                {
-                                 double ray_angle = (s * (fov / 
(sample_count-1))) - fov/2.0;
-                                 pts[2*s+2] = (float)(samples[s].range * 
cos(ray_angle) );
-                                 pts[2*s+3] = (float)(samples[s].range * 
sin(ray_angle) );
-                                 
-                                 // if the sample is unusually bright, draw a 
little blob
-                                 if( samples[s].reflectance > 0 )
-                                        {
-                                               glBegin( GL_POINTS );
-                                               glVertex2f( pts[2*s+2], 
pts[2*s+3] );
-                                               glEnd();
-                                        }                       
-                               }
-                        PopColor();
-                        
-                        glDepthMask( GL_FALSE );
-                        
+                                 glBegin( GL_POINTS );
+                                 glVertex2f( pts[2*s+2], pts[2*s+3] );
+                                 glEnd();
+                               }                        
+                 }
+               
+               glVertexPointer( 2, GL_FLOAT, 0, pts );      
+               
+               PopColor();
+               
+               if( showLaserData )
+                 {                              
                         // draw the filled polygon in transparent blue
                         PushColor( 0, 0, 1, 0.1 );             
-                        glVertexPointer( 2, GL_FLOAT, 0, pts );      
                         glDrawArrays( GL_POLYGON, 0, sample_count+1 );
                         PopColor();
                  }
                
       if( showLaserStrikes )
                  {
-                        // draw the beam strike points in black
-                        PushColor( 0, 0, 0, 1.0 );
-                        glPointSize( 1.0 );
+                        // draw the beam strike points
+                        PushColor( 0, 0, 1, 0.8 );
                         glDrawArrays( GL_POINTS, 0, sample_count+1 );
                         PopColor();
                  }

Modified: code/stage/trunk/libstage/model_load.cc
===================================================================
--- code/stage/trunk/libstage/model_load.cc     2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/libstage/model_load.cc     2008-12-05 22:31:14 UTC (rev 
7189)
@@ -138,21 +138,15 @@
                         blockgroup.CalcSize();
 
                         double epsilon = 0.01;       
-                        double width = blockgroup.size.x;
-                        double height = blockgroup.size.y;
-                        double dx = width/2.0;
-                        double dy = height/2.0;
-                        double dz = blockgroup.size.z;
+                        stg_size_t bgsize = blockgroup.GetSize();
 
-                        // add thin bounding blocks
-                        AddBlockRect(-dx,-dy, epsilon, height, dz );         
-                        AddBlockRect(-dx,-dy, width, epsilon, dz );          
-                        AddBlockRect(-dx, -dy+height-epsilon, width, epsilon, 
dz );
-                        AddBlockRect(-dx+width-epsilon,-dy, epsilon, height, 
dz );
+                        AddBlockRect(blockgroup.minx,blockgroup.miny, epsilon, 
bgsize.y, bgsize.z );         
+                        AddBlockRect(blockgroup.minx,blockgroup.miny, 
bgsize.x, epsilon, bgsize.z );         
+                        AddBlockRect(blockgroup.minx,blockgroup.maxy-epsilon, 
bgsize.x, epsilon, bgsize.z );         
+                        AddBlockRect(blockgroup.maxx-epsilon,blockgroup.miny, 
epsilon, bgsize.y, bgsize.z );         
                  }     
     }    
 
-  
     if( wf->PropertyExists( wf_entity, "mass" ))
     this->SetMass( wf->ReadFloat(wf_entity, "mass", this->mass ));
 
@@ -206,7 +200,7 @@
     this->Say( wf->ReadString(wf_entity, "say", NULL ));
 
   // call any type-specific load callbacks
-  this->CallCallbacks( &this->load_hook );
+  this->CallCallbacks( &this->hook_load );
 
   // MUST BE THE LAST THING LOADED
   if( wf->PropertyExists( wf_entity, "alwayson" ))
@@ -261,7 +255,7 @@
         }
 
   // call any type-specific save callbacks
-  this->CallCallbacks( &this->save_hook );
+  this->CallCallbacks( &this->hook_save );
 
   PRINT_DEBUG1( "Model \"%s\" saving complete.", token );
 }

Modified: code/stage/trunk/libstage/region.cc
===================================================================
--- code/stage/trunk/libstage/region.cc 2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/region.cc 2008-12-05 22:31:14 UTC (rev 7189)
@@ -16,7 +16,7 @@
 Region::Region() 
   : count(0)
 { 
-  for( int i=0; i<Region::SIZE; i++ )
+  for( unsigned int i=0; i<Region::SIZE; i++ )
         cells[i].region = this;
 }
 
@@ -33,7 +33,7 @@
   origin.y = y;
 
   // initialize the parent pointer for all my child regions
-  for( int i=0; i<SuperRegion::SIZE; i++ )
+  for( unsigned int i=0; i<SuperRegion::SIZE; i++ )
         regions[i].superregion = this;
 }
 

Modified: code/stage/trunk/libstage/stage.cc
===================================================================
--- code/stage/trunk/libstage/stage.cc  2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/stage.cc  2008-12-05 22:31:14 UTC (rev 7189)
@@ -233,6 +233,7 @@
   return( pixels + index );
 }
 
+/*
 static void pb_set_pixel( Fl_Shared_Image* pb, int x, int y, uint8_t val )
 {
        // bounds checking
@@ -249,6 +250,7 @@
        else
                PRINT_WARN4( "pb_set_pixel coordinate %d,%d out of range (image 
dimensions %d by %d)", x, y, width, height );
 }
+*/
 
 // set all the pixels in a rectangle 
 static void pb_set_rect( Fl_Shared_Image* pb, int x, int y, int width, int 
height, uint8_t val )

Modified: code/stage/trunk/libstage/stage.hh
===================================================================
--- code/stage/trunk/libstage/stage.hh  2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/stage.hh  2008-12-05 22:31:14 UTC (rev 7189)
@@ -288,6 +288,7 @@
         stg_pose_t() : x(0.0), y(0.0), z(0.0), a(0.0)
         { /*empty*/ }           
 
+         virtual ~stg_pose_t(){};
          
         static stg_pose_t Random( stg_meters_t xmin, stg_meters_t xmax, 
                                                                                
stg_meters_t ymin, stg_meters_t ymax )
@@ -300,7 +301,7 @@
 
         virtual void Print( const char* prefix )
         {
-               printf( "%d pose [x:%.3f y:%.3f a:%.3f]\n",
+               printf( "%s pose [x:%.3f y:%.3f z:%.3f a:%.3f]\n",
                                  prefix, x,y,z,a );
         }
   };
@@ -324,7 +325,7 @@
         
         virtual void Print( const char* prefix )
         {
-               printf( "%d velocity [x:%.3f y:%.3f a:%.3f]\n",
+               printf( "%s velocity [x:%.3f y:%.3f z:%3.f a:%.3f]\n",
                                  prefix, x,y,z,a );
         }
   };
@@ -337,7 +338,7 @@
         stg_pose_t pose; //< position
         stg_size_t size; //< extent
         
-        virtual void Print( const char* prefix )
+        void Print( const char* prefix )
         {
                printf( "%s geom pose: (%.2f,%.2f,%.2f) size: [%.2f,%.2f]\n",
                                  prefix,
@@ -360,14 +361,18 @@
         stg_color_t color;
   };
 
-  /** bound a range of values, from min to max */
-  typedef struct
+  /** bound a range of values, from min to max. min and max are initialized to 
zero. */
+  class  stg_bounds_t
   {
+  public:
         double min; //< smallest value in range
         double max; //< largest value in range
-  } stg_bounds_t;
-
-  /** bound a volume along the x,y,z axes */
+        
+        stg_bounds_t() : min(0), max(0) 
+        { /* empty*/  };
+  };
+  
+  /** bound a volume along the x,y,z axes. All bounds initialized to zero. */
   typedef struct
   {
         stg_bounds_t x; //< volume extent along x axis
@@ -375,14 +380,8 @@
         stg_bounds_t z; //< volume extent along z axis 
   } stg_bounds3d_t;
 
-  /** bound a range of range values, from min to max */
-  typedef struct
-  {
-        stg_meters_t min; //< smallest value in range
-        stg_meters_t max; //< largest value in range
-  } stg_range_bounds_t;
 
-  /** define a three-dimensional bounding box */
+  /** define a three-dimensional bounding box, initialized to zero */
   typedef struct
   {
         stg_bounds_t x, y, z;
@@ -394,7 +393,7 @@
         stg_bounds_t range; //< min and max range of sensor
         stg_radians_t angle; //< width of viewing angle of sensor
   } stg_fov_t;
-
+  
   /** define a point on a 2d plane */
   typedef struct
   {
@@ -881,21 +880,44 @@
   
         static GList* world_list; ///< all the worlds that exist
         static bool quit_all; ///< quit all worlds ASAP  
+        static void UpdateCb( StgWorld* world);
         static unsigned int next_id; ///<initially zero, used to allocate 
unique sequential world ids
         
-        stg_usec_t real_time_start; ///< the real time at which this world was 
created
         bool destroy;
-        bool quit; ///< quit this world ASAP  
-        stg_usec_t real_time_now; ///< The current real time in microseconds
         bool dirty; ///< iff true, a gui redraw would be required
-        int total_subs; ///< the total number of subscriptions to all models
-        double ppm; ///< the resolution of the world model in pixels per meter 
 
         GHashTable* models_by_name; ///< the models that make up the world, 
indexed by name
- 
+        double ppm; ///< the resolution of the world model in pixels per meter 
  
+        bool quit; ///< quit this world ASAP  
         /** StgWorld::quit is set true when this simulation time is reached */
         stg_usec_t quit_time;
+        stg_usec_t real_time_now; ///< The current real time in microseconds
+        stg_usec_t real_time_start; ///< the real time at which this world was 
created
+        GMutex* thread_mutex;
+        GThreadPool *threadpool;
+        int total_subs; ///< the total number of subscriptions to all models
+        unsigned int update_jobs_pending;
+        GList* velocity_list; ///< Models with non-zero velocity and should 
have their poses updated
+        unsigned int worker_threads;
+        GCond* worker_threads_done;
 
-        // hint that the world needs to be redrawn if a GUI is attached
+  protected:    
+  
+        stg_bounds3d_t extent; ///< Describes the 3D volume of the world
+        bool graphics;///< true iff we have a GUI
+        stg_usec_t interval_sim; ///< temporal resolution: milliseconds that 
elapse between simulated time steps 
+        GList* ray_list;///< List of rays traced for debug visualization
+        stg_usec_t sim_time; ///< the current sim time in this world in ms
+        GHashTable* superregions;
+        SuperRegion* sr_cached; ///< The last superregion looked up by this 
world
+        GList* update_list; ///< Models that have a subscriber or controller, 
and need to be updated
+        long unsigned int updates; ///< the number of simulated time steps 
executed so far
+        Worldfile* wf; ///< If set, points to the worldfile used to create 
this world
+
+  public:
+        static const int DEFAULT_PPM = 50;  // default resolution in pixels 
per meter
+        static const stg_msec_t DEFAULT_INTERVAL_SIM = 100;  ///< duration of 
sim timestep
+
+        /** hint that the world needs to be redrawn if a GUI is attached */
         void NeedRedraw(){ dirty = true; };
 
         void LoadModel( Worldfile* wf, int entity, GHashTable* entitytable );
@@ -958,22 +980,6 @@
                                                 const uint32_t sample_count,
                                                 const bool ztest );
   
-  protected:
-        
-        static void UpdateCb( StgWorld* world);
-  
-        GHashTable* superregions;
-        stg_usec_t interval_sim; ///< temporal resolution: milliseconds that 
elapse between simulated time steps 
-        stg_usec_t sim_time; ///< the current sim time in this world in ms
-        GList* ray_list;///< List of rays traced for debug visualization
-        Worldfile* wf; ///< If set, points to the worldfile used to create 
this world
-        bool graphics;///< true iff we have a GUI
-        stg_bounds3d_t extent; ///< Describes the 3D volume of the world
-        long unsigned int updates; ///< the number of simulated time steps 
executed so far
-        FileManager fileMan; ///< Used to load and save worldfiles
-        SuperRegion* sr_cached; ///< The last superregion looked up by this 
world
-        GList* velocity_list; ///< Models with non-zero velocity and should 
have their poses updated
-        GList* update_list; ///< Models that have a subscriber or controller, 
and need to be updated
 
         /** Enlarge the bounding volume to include this point */
         void Extend( stg_point3_t pt );
@@ -1011,54 +1017,44 @@
                velocity_list = g_list_remove( velocity_list, mod );
         }
         
-        static void update_thread_entry( StgModel* mod, void* count );
+        static void update_thread_entry( StgModel* mod, StgWorld* world );
         
-        GMutex* thread_mutex;
-        GCond* worker_threads_done;
-        GThreadPool *threadpool;
-        unsigned int worker_threads;
-
   public:
-        static const int DEFAULT_PPM = 50;  // default resolution in pixels 
per meter
-        static const stg_msec_t DEFAULT_INTERVAL_SIM = 100;  ///< duration of 
sim timestep
-        static bool UpdateAll(); //returns true when time to quit, false 
otherwise
-  
+        /** returns true when time to quit, false otherwise */
+        static bool UpdateAll(); 
+        
         StgWorld( const char* token = "MyWorld", 
                                  stg_msec_t interval_sim = 
DEFAULT_INTERVAL_SIM,
                                  double ppm = DEFAULT_PPM );
-  
+        
         virtual ~StgWorld();
   
         stg_usec_t SimTimeNow(void){ return sim_time; }
         stg_usec_t RealTimeNow(void);
         stg_usec_t RealTimeSinceStart(void);
-  
+        
         stg_usec_t GetSimInterval(){ return interval_sim; };
-  
+        
         Worldfile* GetWorldFile(){ return wf; };
-  
+        
         inline virtual bool IsGUI() { return false; }
-  
+        
         virtual void Load( const char* worldfile_path );
         virtual void UnLoad();
         virtual void Reload();
         virtual bool Save( const char* filename );
         virtual bool Update(void);
-  
+        
         bool TestQuit(){ return( quit || quit_all );  }
         void Quit(){ quit = true; }
         void QuitAll(){ quit_all = true; }
         void CancelQuit(){ quit = false; }
         void CancelQuitAll(){ quit_all = false; }
-
+        
         /** Get the resolution in pixels-per-metre of the underlying
                  discrete raytracing model */ 
         double Resolution(){ return ppm; };
-  
-        /** Returns a pointer to the model identified by ID, or NULL if
-                 nonexistent */
-        //StgModel* GetModel( const stg_id_t id );
-  
+   
         /** Returns a pointer to the model identified by name, or NULL if
                  nonexistent */
         StgModel* GetModel( const char* name );
@@ -1068,11 +1064,6 @@
   
         /** Return the number of times the world has been updated. */
         long unsigned int GetUpdateCount() { return updates; }
-                       
-  
-//      stg_point_t* LocalToGlobal( double scalex, double scaley, 
-//                                                                             
  stg_point_t pts[],
-//                                                                             
  uint32_t pt_count );
   };
 
 class StgBlock
@@ -1130,16 +1121,18 @@
   StgModel* TestCollision();
   
     void SwitchToTestedCells();
-        
-        void Load( Worldfile* wf, int entity );
-        
-        StgModel* mod; //< model to which this block belongs
-        
-        stg_color_t GetColor();
-        
-  private:
-        stg_point_t* pts; //< points defining a polygon
+  
+  void Load( Worldfile* wf, int entity );
+  
+  StgModel* GetModel(){ return mod; };
+  
+  stg_color_t GetColor();
+  
+private:
+   StgModel* mod; //< model to which this block belongs
+  
         size_t pt_count; //< the number of points
+    stg_point_t* pts; //< points defining a polygon
         
         stg_size_t size;
 
@@ -1173,19 +1166,26 @@
 
   class BlockGroup
   {
- 
+        friend class StgModel;
+
   private:
         int displaylist;
         void BuildDisplayList( StgModel* mod );
 
-  public:
         GList* blocks;
         uint32_t count;
         stg_size_t size;
         stg_point3_t offset;
+        stg_meters_t minx, maxx, miny, maxy;
 
+  public:
         BlockGroup();
         ~BlockGroup();
+        
+        GList* GetBlocks(){ return blocks; };
+        uint32_t GetCount(){ return count; };
+        stg_size_t GetSize(){ return size; };
+        stg_point3_t GetOffset(){ return offset; };
 
         /** establish the min and max of all the blocks, so we can scale this
                  group later */
@@ -1231,85 +1231,87 @@
         /** the number of models instatiated - used to assign unique IDs */
         static uint32_t count;
         static GHashTable*  modelsbyid;
-        /** unique process-wide identifier for this model */
-        uint32_t id;   
         std::vector<Option*> drawOptions;
         const std::vector<Option*>& getOptions() const { return drawOptions; }
 
   protected:
-        static const char* typestr;
+        //static const char* typestr;
   
-        stg_pose_t pose;
-        stg_velocity_t velocity;
-        stg_watts_t watts; //< power consumed by this model
-        stg_color_t color;
-        stg_kg_t mass;
+        GMutex* access_mutex;
+        GPtrArray* blinkenlights;  
+        bool blob_return;
+        BlockGroup blockgroup;
+        /**  OpenGL display list identifier for the blockgroup */
+        int blocks_dl;
+
+        int boundary;
+
+        /** callback functions can be attached to any field in this
+                 structure. When the internal function 
model_change(<mod>,<field>)
+                 is called, the callback is triggered */
+        GHashTable* callbacks;
+
+        stg_color_t color;
+        /** This can be set to indicate that the model has new data that
+          may be of interest to users. This allows polling the model
+          instead of adding a data callback. */
+        bool data_fresh;
+        stg_bool_t disabled; //< if non-zero, the model is disabled  
+        int fiducial_key;
+        int fiducial_return;
+        GList* flag_list;
         stg_geom_t geom;
-        stg_laser_return_t laser_return;
-        int obstacle_return;
-        int blob_return;
-        int gripper_return;
-        int ranger_return;
-        int fiducial_return;
-        int fiducial_key;
-        int boundary;
-        stg_meters_t map_resolution;
-        stg_bool_t stall;
-        StgModel* parent; //< the model that owns this one, possibly NUL
-        GArray* trail;
         stg_pose_t global_pose;
-        bool rebuild_displaylist; //< iff true, regenerate block display list 
before redraw
         bool gpose_dirty; //< set this to indicate that global pose may have 
changed  
-        bool map_caches_are_invalid;
-        int subs;     //< the number of subscriptions to this model
-        bool used;    //< TRUE iff this model has been returned by 
GetUnusedModelOfType()  
-        stg_usec_t interval; //< time between updates in us
-        stg_usec_t last_update; //< time of last update in us  
-        stg_bool_t disabled; //< if non-zero, the model is disabled  
-        char* say_string;   //< if non-null, this string is displayed in the 
GUI 
-        StgWorld* world; // pointer to the world in which this model exists
-        ctrlinit_t* initfunc;
-        GList* flag_list;
-        Worldfile* wf;
-        int wf_entity;
-        GPtrArray* blinkenlights;  
-        int blocks_dl; //< OpenGL display list identifier   
-        stg_model_type_t type;  
-        BlockGroup blockgroup;
-        bool has_default_block;
-        bool on_velocity_list;
-        bool on_update_list;
-
+        bool gripper_return;
+        int gui_grid;
+        int gui_mask;
         int gui_nose;
-        int gui_grid;
         int gui_outline;
-        int gui_mask;
-  
+        bool has_default_block;
         /* hooks for attaching special callback functions (not used as
                 variables) */
-        char startup_hook, shutdown_hook, load_hook, save_hook, update_hook;
-
+        char hook_load;
+        char hook_save;
+        char hook_shutdown;
+        char hook_startup;
+        char hook_update;
+        /** unique process-wide identifier for this model */
+        uint32_t id;   
+        ctrlinit_t* initfunc;
+        stg_usec_t interval; //< time between updates in us
+        stg_laser_return_t laser_return;
+        stg_usec_t last_update; //< time of last update in us  
+        bool map_caches_are_invalid;
+        stg_meters_t map_resolution;
+        stg_kg_t mass;
+        bool obstacle_return;
+        bool on_update_list;
+        bool on_velocity_list;
+        StgModel* parent; //< the model that owns this one, possibly NUL
         /** GData datalist can contain arbitrary named data items. Can be used
                  by derived model types to store properties, and for user code
                  to associate arbitrary items with a model. */
+        stg_pose_t pose;
         GData* props;
+        bool ranger_return;
+        bool rebuild_displaylist; //< iff true, regenerate block display list 
before redraw
+        char* say_string;   //< if non-null, this string is displayed in the 
GUI 
 
-        /** callback functions can be attached to any field in this
-                 structure. When the internal function 
model_change(<mod>,<field>)
-                 is called, the callback is triggered */
-        GHashTable* callbacks;
-  
-        bool data_fresh; ///< this can be set to indicate that the model has
-        ///new data that may be of interest to users. This
-        ///allows polling the model instead of adding a
-        ///data callback.  
-        
+        stg_bool_t stall;
         /** Thread safety flag. Iff true, Update() may be called in
                  parallel with other models. Defaults to false for safety */
+        int subs;     //< the number of subscriptions to this model
         bool thread_safe;
-
-        GMutex* access_mutex;
-        
+        GArray* trail;
+        stg_model_type_t type;  
+        bool used;    //< TRUE iff this model has been returned by 
GetUnusedModelOfType()  
+        stg_velocity_t velocity;
+        stg_watts_t watts; //< power consumed by this model
+        Worldfile* wf;
+        int wf_entity;
+        StgWorld* world; // pointer to the world in which this model exists
+        
   public:
         void Lock()
         { 
@@ -1657,34 +1659,34 @@
                 some implementation detail */
        
         void AddStartupCallback( stg_model_callback_t cb, void* user )
-        { AddCallback( &startup_hook, cb, user ); };
+        { AddCallback( &hook_startup, cb, user ); };
        
         void RemoveStartupCallback( stg_model_callback_t cb )
-        { RemoveCallback( &startup_hook, cb ); };
+        { RemoveCallback( &hook_startup, cb ); };
        
         void AddShutdownCallback( stg_model_callback_t cb, void* user )
-        { AddCallback( &shutdown_hook, cb, user ); };
+        { AddCallback( &hook_shutdown, cb, user ); };
        
         void RemoveShutdownCallback( stg_model_callback_t cb )
-        { RemoveCallback( &shutdown_hook, cb ); }
+        { RemoveCallback( &hook_shutdown, cb ); }
        
         void AddLoadCallback( stg_model_callback_t cb, void* user )
-        { AddCallback( &load_hook, cb, user ); }
+        { AddCallback( &hook_load, cb, user ); }
        
         void RemoveLoadCallback( stg_model_callback_t cb )
-        { RemoveCallback( &load_hook, cb ); }
+        { RemoveCallback( &hook_load, cb ); }
        
         void AddSaveCallback( stg_model_callback_t cb, void* user )
-        { AddCallback( &save_hook, cb, user ); }
+        { AddCallback( &hook_save, cb, user ); }
        
         void RemoveSaveCallback( stg_model_callback_t cb )
-        { RemoveCallback( &save_hook, cb ); }
+        { RemoveCallback( &hook_save, cb ); }
        
         void AddUpdateCallback( stg_model_callback_t cb, void* user )
-        { AddCallback( &update_hook, cb, user ); }
+        { AddCallback( &hook_update, cb, user ); }
        
         void RemoveUpdateCallback( stg_model_callback_t cb )
-        { RemoveCallback( &update_hook, cb ); }
+        { RemoveCallback( &hook_update, cb ); }
        
         /** named-property interface 
          */
@@ -1892,17 +1894,19 @@
         friend class StgModelCamera;
 
   private:
-        bool paused; ///< the world only updates when this is false
-        //int wf_section;
+
         StgCanvas* canvas;
+        std::vector<Option*> drawOptions;
+        FileManager fileMan; ///< Used to load and save worldfiles
+        stg_usec_t interval_log[INTERVAL_LOG_LEN];
+        stg_usec_t interval_real;   ///< real-time interval between updates - 
set this to zero for 'as fast as possible
         Fl_Menu_Bar* mbar;
         OptionsDlg* oDlg;
-        std::vector<Option*> drawOptions;
-        void updateOptions();
-        stg_usec_t interval_log[INTERVAL_LOG_LEN];
+        bool pause_time;
+        bool paused; ///< the world only updates when this is false
+        stg_usec_t real_time_of_last_update;
 
-        stg_usec_t real_time_of_last_update;
-        stg_usec_t interval_real;   ///< real-time interval between updates - 
set this to zero for 'as fast as possible
+        void UpdateOptions();
        
         // static callback functions
         static void windowCb( Fl_Widget* w, void* p ); 
@@ -1917,10 +1921,7 @@
         // GUI functions
         bool saveAsDialog();
         bool closeWindowQuery();
-       
-        // Quit time pause
-        bool pause_time;
-       
+               
         virtual void AddModel( StgModel* mod );
 
   protected:
@@ -1934,7 +1935,6 @@
         StgCanvas* GetCanvas( void ) { return canvas; }
 
   public:
-        static const stg_msec_t DEFAULT_INTERVAL_REAL = 100; ///< real time 
between updates
        
         StgWorldGui(int W,int H,const char*L=0);
         ~StgWorldGui();
@@ -1952,7 +1952,10 @@
         void Start(){ paused = false; };
         void Stop(){ paused = true; };
         void TogglePause(){ paused = !paused; };
-       
+        
+        /** show the window - need to call this if you don't Load(). */
+        void Show(); 
+
         /** Get human readable string that describes the current simulation
                  time. */
         std::string ClockString( void );
@@ -2081,7 +2084,7 @@
   {
         uint32_t sample_count;
         uint32_t resolution;
-        stg_range_bounds_t range_bounds;
+        stg_bounds_t range_bounds;
         stg_radians_t fov;
         stg_usec_t interval;
   } stg_laser_cfg_t;
@@ -2090,8 +2093,6 @@
   class StgModelLaser : public StgModel
   {
   private:
-        int dl_debug_laser;
-  
         /** OpenGL displaylist for laser data */
         int data_dl; 
         bool data_dirty;

Modified: code/stage/trunk/libstage/world.cc
===================================================================
--- code/stage/trunk/libstage/world.cc  2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/libstage/world.cc  2008-12-05 22:31:14 UTC (rev 7189)
@@ -53,10 +53,6 @@
 bool StgWorld::quit_all = false;
 GList* StgWorld::world_list = NULL;
 
-const unsigned int THREAD_COUNT = 8;
-
-gint update_jobs_pending=0;
-
 static guint PointIntHash( stg_point_int_t* pt )
 {
        return( pt->x + (pt->y<<16 ));
@@ -68,6 +64,63 @@
 }
 
 
+StgWorld::StgWorld( const char* token, 
+                                                 stg_msec_t interval_sim,
+                                                 double ppm )
+  : 
+  // private
+  destroy( false ),
+  dirty( true ),
+  models_by_name( g_hash_table_new( g_str_hash, g_str_equal ) ),
+  ppm( ppm ), // raytrace resolution
+  quit( false ),
+  quit_time( 0 ),
+  real_time_now( RealTimeNow() ),
+  real_time_start( real_time_now ),
+  thread_mutex( g_mutex_new() ),
+  threadpool( NULL ),
+  total_subs( 0 ), 
+  update_jobs_pending(0),
+  velocity_list( NULL ),
+  worker_threads( 0 ),
+  worker_threads_done( g_cond_new() ),
+
+  // protected
+  extent(),
+  graphics( false ), 
+  interval_sim( (stg_usec_t)thousand * interval_sim ),
+  ray_list( NULL ),  
+  sim_time( 0 ),
+  superregions( g_hash_table_new( (GHashFunc)PointIntHash, 
+                                                                               
         (GEqualFunc)PointIntEqual ) ),
+  sr_cached(NULL),
+  update_list( NULL ),
+  updates( 0 ),
+  wf( NULL )
+{
+  if( ! Stg::InitDone() )
+        {
+               PRINT_WARN( "Stg::Init() must be called before a StgWorld is 
created." );
+               exit(-1);
+        }
+  
+  StgWorld::world_list = g_list_append( StgWorld::world_list, this );
+}
+
+
+StgWorld::~StgWorld( void )
+{
+       PRINT_DEBUG2( "destroying world %d %s", id, token );
+
+       if( wf ) delete wf;
+
+       g_hash_table_destroy( models_by_name );
+       g_free( token );
+
+       world_list = g_list_remove( world_list, this );
+}
+
+
 SuperRegion* StgWorld::CreateSuperRegion( int32_t x, int32_t y )
 {
        SuperRegion* sr = new SuperRegion( x, y );
@@ -94,74 +147,21 @@
   return quit;
 }
 
-void StgWorld::update_thread_entry( StgModel* mod, void* dummy )
+void StgWorld::update_thread_entry( StgModel* mod, StgWorld* world )
 {
   mod->Update();
   
-  g_mutex_lock( mod->world->thread_mutex );
+  g_mutex_lock( world->thread_mutex );
   
-  update_jobs_pending--;
+  world->update_jobs_pending--;
   
-  if( update_jobs_pending == 0 )
-        g_cond_signal( mod->world->worker_threads_done );
+  if( world->update_jobs_pending == 0 )
+        g_cond_signal( world->worker_threads_done );
   
-  g_mutex_unlock( mod->world->thread_mutex );
+  g_mutex_unlock( world->thread_mutex );
 }
 
 
-StgWorld::StgWorld( const char* token, 
-                                                 stg_msec_t interval_sim,
-                                                 double ppm )
-  : 
-  ray_list( NULL ),
-  quit_time( 0 ),
-  quit( false ),
-  updates( 0 ),
-  wf( NULL ),
-  graphics( false ), 
-  models_by_name( g_hash_table_new( g_str_hash, g_str_equal ) ),
-  sim_time( 0 ),
-  interval_sim( (stg_usec_t)thousand * interval_sim ),
-  ppm( ppm ), // raytrace resolution
-  real_time_start( RealTimeNow() ),
-  superregions( g_hash_table_new( (GHashFunc)PointIntHash, 
-                                                                               
         (GEqualFunc)PointIntEqual ) ),
-  total_subs( 0 ),
-  destroy( false ),
-  real_time_now( 0 ),
-  velocity_list( NULL ),
-  update_list( NULL ),
-  sr_cached(NULL),
-  worker_threads( 0 ),
-  threadpool( NULL ),
-  thread_mutex( g_mutex_new() ),
-  worker_threads_done( g_cond_new() )
-{
-  if( ! Stg::InitDone() )
-        {
-               PRINT_WARN( "Stg::Init() must be called before a StgWorld is 
created." );
-               exit(-1);
-        }
-
-  bzero( &extent, sizeof(extent) );
-  
-  StgWorld::world_list = g_list_append( StgWorld::world_list, this );
-}
-
-
-StgWorld::~StgWorld( void )
-{
-       PRINT_DEBUG2( "destroying world %d %s", id, token );
-
-       if( wf ) delete wf;
-
-       g_hash_table_destroy( models_by_name );
-       g_free( token );
-
-       world_list = g_list_remove( world_list, this );
-}
-
-
 void StgWorld::RemoveModel( StgModel* mod )
 {
        g_hash_table_remove( models_by_name, mod );
@@ -293,7 +293,7 @@
                          
                          if( threadpool == NULL )
                                 threadpool = g_thread_pool_new( 
(GFunc)update_thread_entry, 
-                                                                               
                                        NULL,
+                                                                               
                                        this,
                                                                                
                                        worker_threads, 
                                                                                
                                        true,
                                                                                
                                        NULL );
@@ -334,9 +334,12 @@
        LISTMETHOD( children, StgModel*, InitRecursive );
        
        stg_usec_t load_end_time = RealTimeNow();
-       
-       printf( "[Load time %.3fsec]\n", 
-                         (load_end_time - load_start_time) / 1000000.0 );
+
+       if( debug )
+         printf( "[Load time %.3fsec]\n", 
+                                (load_end_time - load_start_time) / 1000000.0 
);
+       else
+         putchar( '\n' );
 }
 
 
@@ -755,6 +758,7 @@
 static int _save_cb( StgModel* mod, void* dummy )
 {
        mod->Save();
+       return 0;
 }
 
 bool StgWorld::Save( const char *filename )
@@ -767,6 +771,7 @@
 static int _reload_cb(  StgModel* mod, void* dummy )
 {
        mod->Load();
+       return 0;
 }
 
 // reload the current worldfile

Modified: code/stage/trunk/libstage/worldgui.cc
===================================================================
--- code/stage/trunk/libstage/worldgui.cc       2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/libstage/worldgui.cc       2008-12-05 22:31:14 UTC (rev 
7189)
@@ -154,48 +154,51 @@
 
 StgWorldGui::StgWorldGui(int W,int H,const char* L) : 
   Fl_Window(W,H,L ),
+  canvas( new StgCanvas( this,0,30,W,H-30 ) ),
+  drawOptions(),
+  fileMan(),
+  interval_log(),
+  interval_real( (stg_usec_t)1e5 ),
+  mbar( new Fl_Menu_Bar(0,0, W, 30)),
   oDlg( NULL ),
+  pause_time( false ), 
   paused( false ),
-  //graphics( true ),
-  pause_time( false ), 
-  interval_real( (stg_usec_t)thousand * DEFAULT_INTERVAL_REAL ),
-  mbar( new Fl_Menu_Bar(0,0, W, 30)),
-  canvas( new StgCanvas( this,0,30,W,H-30 ) )
-  {
-        for( unsigned int i=0; i<INTERVAL_LOG_LEN; i++ )
-               interval_log[i] = interval_real;
-        
-        resizable(canvas);
+  real_time_of_last_update( RealTimeNow() )
+{
+  for( unsigned int i=0; i<INTERVAL_LOG_LEN; i++ )
+        interval_log[i] = interval_real;
+  
+  resizable(canvas);
+  
+  end();
+  
+  label( PROJECT );
+  
+  mbar->textsize(12);
+  
+  mbar->add( "&File", 0, 0, 0, FL_SUBMENU );
+  mbar->add( "File/&Load World...", FL_CTRL + 'l', fileLoadCb, this, 
FL_MENU_DIVIDER );
+  mbar->add( "File/&Save World", FL_CTRL + 's', 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/Save Frames, fileScreenshotSaveCb, 
this,FL_MENU_TOGGLE );
+  
+  mbar->add( "File/E&xit", FL_CTRL+'q', StgWorldGui::fileExitCb, this );
+  
+  mbar->add( "&View", 0, 0, 0, FL_SUBMENU );
+  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 );
+  
+  callback( StgWorldGui::windowCb, this );      
 
-        end();
+       show(); 
+}
 
-        label( PROJECT ),
-        
-        mbar->textsize(12);
-        
-        mbar->add( "&File", 0, 0, 0, FL_SUBMENU );
-        mbar->add( "File/&Load World...", FL_CTRL + 'l', fileLoadCb, this, 
FL_MENU_DIVIDER );
-        mbar->add( "File/&Save World", FL_CTRL + 's', 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/Save Frames, fileScreenshotSaveCb, 
this,FL_MENU_TOGGLE );
-        
-        mbar->add( "File/E&xit", FL_CTRL+'q', StgWorldGui::fileExitCb, this );
-        
-        mbar->add( "&View", 0, 0, 0, FL_SUBMENU );
-        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 );
-        
-        callback( StgWorldGui::windowCb, this );
-        
-        show();
-  }
-
 StgWorldGui::~StgWorldGui()
 {
   delete mbar;
@@ -204,6 +207,11 @@
   delete canvas;
 }
 
+void StgWorldGui::Show()
+{
+  show(); // fltk
+}
+
 void StgWorldGui::Load( const char* filename )
 {
   PRINT_DEBUG1( "%s.Load()", token );
@@ -245,7 +253,9 @@
   }
   label( title.c_str() );
        
-  updateOptions();
+  UpdateOptions();
+
+  show();
 }
 
 void StgWorldGui::UnLoad() 
@@ -279,9 +289,6 @@
 
 bool StgWorldGui::Update()
 {
-  if( real_time_of_last_update == 0 )
-    real_time_of_last_update = RealTimeNow();
-
   //pause the simulation if quit time is set
   if( PastQuitTime() && pause_time == false ) {
          TogglePause();
@@ -318,6 +325,9 @@
                }
   } while( interval < interval_real );
   
+  
+  //printf( "interval_real %.20f\n", interval_real );
+
   // if( paused ) // gentle on the CPU when paused
                 //usleep( 10000 );
   
@@ -579,7 +589,7 @@
 
 void StgWorldGui::helpAboutCb( Fl_Widget* w, void* p ) 
 {
-  StgWorldGui* worldGui = static_cast<StgWorldGui*>( p );
+  // StgWorldGui* worldGui = static_cast<StgWorldGui*>( p );
 
   fl_register_images();
        
@@ -683,18 +693,21 @@
   }
 }
 
-void StgWorldGui::updateOptions() {
+void StgWorldGui::UpdateOptions() 
+{
   std::set<Option*, Option::optComp> options;
   std::vector<Option*> modOpts;
-  for( GList* it=update_list; it; it=it->next ) {
-    modOpts = ((StgModel*)it->data)->getOptions();
-    options.insert( modOpts.begin(), modOpts.end() );  
-  }
+  
+  for( GList* it=update_list; it; it=it->next ) 
+        {
+               modOpts = ((StgModel*)it->data)->getOptions();
+               options.insert( modOpts.begin(), modOpts.end() );       
+        }
        
   drawOptions.assign( options.begin(), options.end() );
-  if ( oDlg ) {
-    oDlg->setOptions( drawOptions );
-  }
+  
+  if ( oDlg ) 
+        oDlg->setOptions( drawOptions );
 }
 
 void StgWorldGui::DrawBoundingBoxTree()

Modified: code/stage/trunk/worlds/benchmark/expand.cc
===================================================================
--- code/stage/trunk/worlds/benchmark/expand.cc 2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/worlds/benchmark/expand.cc 2008-12-05 22:31:14 UTC (rev 
7189)
@@ -84,7 +84,6 @@
   
   //printf( "resultant %.2f turn_speed %.2f\n", resultant_angle, turn_speed );
 
-  int forward = 0 ;
   // if the front is clear, drive forwards
   if( (rgr->samples[0] > SAFE_DIST) &&
                (rgr->samples[1] > SAFE_DIST/2.0) &&

Modified: code/stage/trunk/worlds/fasr.world
===================================================================
--- code/stage/trunk/worlds/fasr.world  2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/worlds/fasr.world  2008-12-05 22:31:14 UTC (rev 7189)
@@ -13,8 +13,9 @@
 
 resolution 0.02
 
-# threads don't help here as the per-robot update is very fast
-threadpool 0
+# threads may help here depending on your CPU
+threadpool 3
+# threadpool 2
 
 
 # configure the GUI window

Modified: code/stage/trunk/worlds/simple.world
===================================================================
--- code/stage/trunk/worlds/simple.world        2008-12-04 21:30:45 UTC (rev 
7188)
+++ code/stage/trunk/worlds/simple.world        2008-12-05 22:31:14 UTC (rev 
7189)
@@ -5,7 +5,6 @@
 include "pioneer.inc"
 include "map.inc"
 include "sick.inc"
-include "walle.inc"
 
 interval_sim 100  # simulation timestep in milliseconds
 interval_real 10  # real-time interval between simulation updates in 
milliseconds 
@@ -29,9 +28,9 @@
 floorplan
 ( 
   name "cave"
-  size [17.000 17.000 0.800]
-  pose [8.000 8.000 0 0 ]
- bitmap "bitmaps/cave.png"
+  size [16.000 16.000 0.800]
+  pose [8 8 0 0]
+  bitmap "bitmaps/cave.png"
 )
 
 
@@ -40,10 +39,8 @@
   # can refer to the robot by this name
   name "r0"
 
-  localization "odom"
-
   pose [ 0.892 0.800 0 56.500 ] 
-  sicklaser( samples 180 ) 
+  sicklaser() 
 
   ctrl "wander"
 )

Modified: code/stage/trunk/worlds/walle.inc
===================================================================
--- code/stage/trunk/worlds/walle.inc   2008-12-04 21:30:45 UTC (rev 7188)
+++ code/stage/trunk/worlds/walle.inc   2008-12-05 22:31:14 UTC (rev 7189)
@@ -21,8 +21,6 @@
   size [0.35 0.5 0.5]
   #origin [-0.25 -0.25 0 0 ]
 
-  laser( pose [0.15 0 -0.27 0 ] size [0.01 0.01 0.01] alwayson 1 )
-
   # body bottom
   block 
   (


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

------------------------------------------------------------------------------
SF.Net email is Sponsored by MIX09, March 18-20, 2009 in Las Vegas, Nevada.
The future of the web can't happen without you.  Join us at MIX09 to help
pave the way to the Next Web now. Learn more and register at
http://ad.doubleclick.net/clk;208669438;13503038;i?http://2009.visitmix.com/
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to