Revision: 6903 http://playerstage.svn.sourceforge.net/playerstage/?rev=6903&view=rev Author: alexcb Date: 2008-07-22 20:23:21 +0000 (Tue, 22 Jul 2008)
Log Message: ----------- fixed non-gui mode, and quit_time Modified Paths: -------------- code/stage/trunk/libstage/main.cc code/stage/trunk/libstage/model.cc code/stage/trunk/libstage/model_laser.cc code/stage/trunk/libstage/stage.hh code/stage/trunk/libstage/world.cc code/stage/trunk/libstage/worldgui.cc Modified: code/stage/trunk/libstage/main.cc =================================================================== --- code/stage/trunk/libstage/main.cc 2008-07-22 17:58:47 UTC (rev 6902) +++ code/stage/trunk/libstage/main.cc 2008-07-22 20:23:21 UTC (rev 6903) @@ -51,12 +51,13 @@ bool loaded_world_file = false; + optindex = optind; //points to first non-option while( optindex < argc ) { if( optindex > 0 ) { const char* worldfilename = argv[optindex]; - StgWorldGui* world = new StgWorldGui( 400, 300, worldfilename ); + StgWorld* world = ( usegui ? new StgWorldGui( 400, 300, worldfilename ) : new StgWorld( worldfilename ) ); world->Load( worldfilename ); loaded_world_file = true; } @@ -68,8 +69,15 @@ new StgWorldGui( 400, 300 ); } - - while(true) - StgWorld::UpdateAll(); + if( usegui == true ) { + //don't close the window once time has finished + while( true ) + StgWorld::UpdateAll(); + } else { + //close program once time has completed + bool quit = false; + while( quit == false ) + quit = StgWorld::UpdateAll(); + } } Modified: code/stage/trunk/libstage/model.cc =================================================================== --- code/stage/trunk/libstage/model.cc 2008-07-22 17:58:47 UTC (rev 6902) +++ code/stage/trunk/libstage/model.cc 2008-07-22 20:23:21 UTC (rev 6903) @@ -199,7 +199,8 @@ this->subs = 0; this->stall = false; - this->blocks_dl = glGenLists( 1 ); + if( world->IsGUI() ) + this->blocks_dl = glGenLists( 1 ); this->geom.size.x = DEFAULT_GEOM_SIZEX; this->geom.size.y = DEFAULT_GEOM_SIZEY; Modified: code/stage/trunk/libstage/model_laser.cc =================================================================== --- code/stage/trunk/libstage/model_laser.cc 2008-07-22 17:58:47 UTC (rev 6902) +++ code/stage/trunk/libstage/model_laser.cc 2008-07-22 20:23:21 UTC (rev 6903) @@ -101,7 +101,8 @@ // don't allocate sample buffer memory until Update() is called samples = NULL; - data_dl = glGenLists(1); + if( world->IsGUI() ) + data_dl = glGenLists(1); registerOption( &showLaserData ); registerOption( &showLaserStrikes ); Modified: code/stage/trunk/libstage/stage.hh =================================================================== --- code/stage/trunk/libstage/stage.hh 2008-07-22 17:58:47 UTC (rev 6902) +++ code/stage/trunk/libstage/stage.hh 2008-07-22 20:23:21 UTC (rev 6903) @@ -945,7 +945,7 @@ class Region; class SuperRegion; - + /// %StgWorld class class StgWorld : public StgAncestor { @@ -959,7 +959,7 @@ /** Coordinate system stack - experimental*/ GQueue* csstack; - + void PushPose(); void PopPose(); stg_pose_t* PeekPose(); @@ -988,6 +988,7 @@ virtual void PushColor( stg_color_t col ) { /* do nothing */ }; virtual void PushColor( double r, double g, double b, double a ) { /* do nothing */ }; virtual void PopColor(){ /* do nothing */ }; + /** The current real time in microseconds */ stg_usec_t real_time_now; @@ -1039,6 +1040,7 @@ static void UpdateCb( StgWorld* world); stg_usec_t sim_time; ///< the current sim time in this world in ms + inline bool PastQuitTime() const { return (quit_time > 0) && (sim_time >= quit_time); } GList* ray_list; // store rays traced for debugging purposes @@ -1066,7 +1068,7 @@ 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 void UpdateAll(); + static bool UpdateAll(); //returns true when time to quit, false otherwise StgWorld( const char* token = "MyWorld", stg_msec_t interval_sim = DEFAULT_INTERVAL_SIM, @@ -1087,6 +1089,8 @@ Worldfile* GetWorldFile(){ return wf; }; + inline virtual bool IsGUI() { return false; } + virtual void Load( const char* worldfile_path ); virtual void UnLoad(); virtual void Reload(); @@ -2000,6 +2004,9 @@ bool saveAsDialog(); bool closeWindowQuery(); + // Quit time pause + bool pause_time; + protected: virtual void PushColor( stg_color_t col ) { canvas->PushColor( col ); } @@ -2027,6 +2034,7 @@ virtual void UnLoad(); virtual bool Save( const char* filename ); + inline virtual bool IsGUI() { return true; } void Start(){ paused = false; }; void Stop(){ paused = true; }; Modified: code/stage/trunk/libstage/world.cc =================================================================== --- code/stage/trunk/libstage/world.cc 2008-07-22 17:58:47 UTC (rev 6902) +++ code/stage/trunk/libstage/world.cc 2008-07-22 20:23:21 UTC (rev 6903) @@ -49,7 +49,6 @@ #include "region.hh" #include "file_manager.hh" - // static data members unsigned int StgWorld::next_id = 0; bool StgWorld::quit_all = false; @@ -81,15 +80,19 @@ delete sr; } -void StgWorld::UpdateAll() +bool StgWorld::UpdateAll() { - for( GList* it = StgWorld::world_list; it; it=it->next ) - ((StgWorld*)it->data)->Update(); + bool quit = true; + for( GList* it = StgWorld::world_list; it; it=it->next ) { + if( ((StgWorld*)it->data)->Update() == false ) + quit = false; + } + return quit; } StgWorld::StgWorld( const char* token, stg_msec_t interval_sim, - double ppm ) + double ppm ) { Initialize( token, interval_sim, ppm ); } @@ -223,9 +226,10 @@ wf->ReadInt( entity, "interval_sim", (int)(this->interval_sim/thousand) ); - if( wf->PropertyExists( entity, "quit_time" ) ) + if( wf->PropertyExists( entity, "quit_time" ) ) { this->quit_time = (stg_usec_t)million * - wf->ReadInt( entity, "quit_time", 0 ); + wf->ReadFloat( entity, "quit_time", 0 ); + } if( wf->PropertyExists( entity, "resolution" ) ) this->ppm = @@ -361,6 +365,12 @@ { PRINT_DEBUG( "StgWorld::Update()" ); + // if we've run long enough, exit + if( PastQuitTime() ) { + if( IsGUI() == false ) + return true; + } + // update any models that are due to be updated for( GList* it=this->update_list; it; it=it->next ) ((StgModel*)it->data)->UpdateIfDue(); @@ -371,12 +381,8 @@ this->sim_time += this->interval_sim; this->updates++; - - // if we've run long enough, set the quit flag - if( (quit_time > 0) && (sim_time >= quit_time) ) - quit = true; - - return true; + + return false; } void StgWorld::AddModel( StgModel* mod ) Modified: code/stage/trunk/libstage/worldgui.cc =================================================================== --- code/stage/trunk/libstage/worldgui.cc 2008-07-22 17:58:47 UTC (rev 6902) +++ code/stage/trunk/libstage/worldgui.cc 2008-07-22 20:23:21 UTC (rev 6903) @@ -165,6 +165,8 @@ label( PROJECT ); + pause_time = false; + interval_real = (stg_usec_t)thousand * DEFAULT_INTERVAL_REAL; for( unsigned int i=0; i<INTERVAL_LOG_LEN; i++ ) @@ -288,6 +290,12 @@ 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(); + pause_time = true; + } + bool val = paused ? true : StgWorld::Update(); stg_usec_t interval; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------- This SF.Net email is sponsored by the Moblin Your Move Developer's challenge Build the coolest Linux based applications with Moblin SDK & win great prizes Grand prize is a trip for two to an Open Source event anywhere in the world http://moblin-contest.org/redirect.php?banner_id=100&url=/ _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit