Revision: 6614 http://playerstage.svn.sourceforge.net/playerstage/?rev=6614&view=rev Author: rtv Date: 2008-06-16 20:24:37 -0700 (Mon, 16 Jun 2008)
Log Message: ----------- improving external API. mainly running and updating worlds. also increased speed a bit Modified Paths: -------------- code/stage/trunk/libstage/canvas.cc code/stage/trunk/libstage/main.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/stage.cc code/stage/trunk/libstage/stage.hh code/stage/trunk/libstage/test.cc code/stage/trunk/libstage/world.cc code/stage/trunk/libstage/worldgui.cc code/stage/trunk/worlds/fasr.world Modified: code/stage/trunk/libstage/canvas.cc =================================================================== --- code/stage/trunk/libstage/canvas.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/canvas.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -13,11 +13,11 @@ void StgCanvas::TimerCallback( StgCanvas* c ) { - c->redraw(); - - Fl::repeat_timeout(((double)c->interval/1000), - (Fl_Timeout_Handler)StgCanvas::TimerCallback, - c); + c->redraw(); + + Fl::repeat_timeout(((double)c->interval/1000), + (Fl_Timeout_Handler)StgCanvas::TimerCallback, + c); } @@ -47,10 +47,10 @@ showflags = STG_SHOW_CLOCK | STG_SHOW_BLOCKS | STG_SHOW_GRID | STG_SHOW_DATA; - // start the timer that causes regular redraws - Fl::add_timeout( ((double)interval/1000), - (Fl_Timeout_Handler)StgCanvas::TimerCallback, - this); + // // start the timer that causes regular redraws + Fl::add_timeout( ((double)interval/1000), + (Fl_Timeout_Handler)StgCanvas::TimerCallback, + this); } StgCanvas::~StgCanvas() @@ -133,7 +133,7 @@ //printf("Clicked rByte: 0x%X, gByte: 0x%X, bByte: 0x%X, aByte: 0x%X\n", rByte, gByte, bByte, aByte); //printf("-->model Id = 0x%X\n", modelId); - StgModel* mod = (StgModel*)g_hash_table_lookup( StgModel::modelsbyid, (void*)modelId ); + StgModel* mod = StgModel::LookupId( modelId ); //printf("%p %s %d %x\n", mod, mod ? mod->Token() : "(none)", id, id ); @@ -208,6 +208,7 @@ camera.scale( Fl::event_dy(), Fl::event_x(), w(), Fl::event_y(), h() ); } invalidate(); + redraw(); } return 1; @@ -226,6 +227,7 @@ } invalidate(); + redraw(); } else if( Fl::event_state( FL_ALT ) ) { @@ -319,6 +321,8 @@ } startx = Fl::event_x(); starty = Fl::event_y(); + + redraw(); return 1; // end case FL_DRAG case FL_RELEASE: // mouse button released @@ -347,9 +351,9 @@ world->TogglePause(); break; case ' ': // space bar - camera.resetAngle(); - invalidate(); + //invalidate(); + redraw(); break; case FL_Left: camera.move( -10, 0 ); break; case FL_Right: camera.move( 10, 0 );; break; @@ -565,7 +569,7 @@ // if( loaded_texture == true && use_perspective_camera == true ) // return; - if (!valid() || world->dirty ) + if (!valid() ) { valid(1); FixViewport(w(), h()); Modified: code/stage/trunk/libstage/main.cc =================================================================== --- code/stage/trunk/libstage/main.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/main.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -42,12 +42,16 @@ puts("");// end the first start-up line + + // XX TODO + // initialize libstage Stg::Init( &argc, &argv ); // arguments at index optindex and later are not options, so they // must be world file names + bool loaded_world_file = false; while( optindex < argc ) { @@ -56,19 +60,18 @@ const char* worldfilename = argv[optindex]; StgWorldGui* world = new StgWorldGui( 400, 300, worldfilename ); world->Load( worldfilename ); - world->Start(); loaded_world_file = true; } optindex++; } - if( loaded_world_file == false ) { - // replace this with a loading dialog/window - StgWorldGui* world = new StgWorldGui( 400, 300 ); - } +// if( loaded_world_file == false ) { +// // replace this with a loading dialog/window +// StgWorldGui* world = new StgWorldGui( 400, 300 ); +// } - - - StgWorldGui::Run(); // run all the simulations + + while(true) + StgWorld::UpdateAll(); } Modified: code/stage/trunk/libstage/model.cc =================================================================== --- code/stage/trunk/libstage/model.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/model.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -258,6 +258,8 @@ if( callbacks ) g_hash_table_destroy( callbacks ); + g_hash_table_remove( StgModel::modelsbyid, (void*)id ); + world->RemoveModel( this ); } Modified: code/stage/trunk/libstage/model_laser.cc =================================================================== --- code/stage/trunk/libstage/model_laser.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/model_laser.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -17,23 +17,21 @@ #include "stage_internal.hh" // DEFAULT PARAMETERS FOR LASER MODEL -static const bool DEFAULT_LASER_FILLED = true; -static const stg_watts_t DEFAULT_LASER_WATTS = 17.5; // laser power consumption -static const stg_meters_t DEFAULT_LASER_SIZEX = 0.15; -static const stg_meters_t DEFAULT_LASER_SIZEY = 0.15; -static const stg_meters_t DEFAULT_LASER_SIZEZ = 0.2; -static const stg_meters_t DEFAULT_LASER_MINRANGE = 0.0; -static const stg_meters_t DEFAULT_LASER_MAXRANGE = 8.0; -static const stg_radians_t DEFAULT_LASER_FOV = M_PI; -static const unsigned int DEFAULT_LASER_SAMPLES = 180; -static const stg_msec_t DEFAULT_LASER_INTERVAL_MS = 100; -static const unsigned int DEFAULT_LASER_RESOLUTION = 1; +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 char LASER_GEOM_COLOR[] = "blue"; -//static const char LASER_BRIGHT_COLOR[] = "blue"; -//static const char LASER_CFG_COLOR[] = "light steel blue"; -//static const char LASER_COLOR[] = "steel blue"; -//static const char LASER_FILL_COLOR[] = "powder blue"; +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"; /** @ingroup model @@ -83,24 +81,22 @@ id, typestr ); // sensible laser defaults - interval = 1e3 * DEFAULT_LASER_INTERVAL_MS; + interval = 1e3 * StgModelLaser::DEFAULT_INTERVAL_MS; laser_return = LaserVisible; stg_geom_t geom; memset( &geom, 0, sizeof(geom)); - geom.size.x = DEFAULT_LASER_SIZEX; - geom.size.y = DEFAULT_LASER_SIZEY; - geom.size.z = DEFAULT_LASER_SIZEZ; + geom.size = StgModelLaser::DEFAULT_SIZE; SetGeom( geom ); // set default color - SetColor( stg_lookup_color(LASER_GEOM_COLOR)); + SetColor( stg_lookup_color(DEFAULT_GEOM_COLOR)); - range_min = DEFAULT_LASER_MINRANGE; - range_max = DEFAULT_LASER_MAXRANGE; - fov = DEFAULT_LASER_FOV; - sample_count = DEFAULT_LASER_SAMPLES; - resolution = DEFAULT_LASER_RESOLUTION; + range_min = DEFAULT_MINRANGE; + range_max = DEFAULT_MAXRANGE; + fov = DEFAULT_FOV; + sample_count = DEFAULT_SAMPLES; + resolution = DEFAULT_RESOLUTION; // don't allocate sample buffer memory until Update() is called samples = NULL; @@ -237,7 +233,7 @@ PRINT_DEBUG( "laser startup" ); // start consuming power - SetWatts( DEFAULT_LASER_WATTS ); + SetWatts( StgModelLaser::DEFAULT_WATTS ); } void StgModelLaser::Shutdown( void ) Modified: code/stage/trunk/libstage/model_load.cc =================================================================== --- code/stage/trunk/libstage/model_load.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/model_load.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -33,7 +33,7 @@ { //printf( "changed %s to %s\n", this->token, token ); this->token = strdup( name ); - world->AddModelName( this ); // add this name to the world's table + world->AddModel( this ); // add this name to the world's table } else PRINT_ERR1( "Name blank for model %s. Check your worldfile\n", this->token ); Modified: code/stage/trunk/libstage/stage.cc =================================================================== --- code/stage/trunk/libstage/stage.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/stage.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -23,6 +23,7 @@ stg_typetable_entry_t Stg::typetable[MODEL_TYPE_COUNT]; + void Stg::Init( int* argc, char** argv[] ) { PRINT_DEBUG( "Stg::Init()" ); Modified: code/stage/trunk/libstage/stage.hh =================================================================== --- code/stage/trunk/libstage/stage.hh 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/stage.hh 2008-06-17 03:24:37 UTC (rev 6614) @@ -84,13 +84,18 @@ /** The Stage library uses its own namespace */ namespace Stg { + // foreward declare + class StgCanvas; + class Worldfile; + class StgWorld; + class StgModel; + /** Initialize the Stage library */ void Init( int* argc, char** argv[] ); /** returns true iff Stg::Init() has been called. */ bool InitDone(); - - + /** Create unique identifying numbers for each type of model, and a count of the number of types. */ typedef enum { @@ -106,9 +111,6 @@ // types } stg_model_type_t; - // foreward declare - class StgCanvas; - class Worldfile; /// Copyright string const char COPYRIGHT[] = @@ -971,8 +973,15 @@ friend class StgTime; friend class StgCanvas; +public: + static void UpdateAll(); + private: + static GList* world_list; + /** Update all existing worlds */ + + static bool quit_all; // quit all worlds ASAP static unsigned int next_id; //< initialized to zero, used tob //allocate unique sequential world ids @@ -1010,8 +1019,9 @@ GList* velocity_list; ///< a list of models that have non-zero velocity, for efficient updating stg_usec_t sim_time; ///< the current sim time in this world in ms - stg_usec_t wall_last_update; ///< the real time of the last update in ms + //stg_usec_t wall_last_update; ///< the real time of the last update in ms + long unsigned int updates; ///< the number of simulated time steps executed so far bool dirty; ///< iff true, a gui redraw would be required @@ -1026,7 +1036,6 @@ bool paused; ///< the world only updates when this is false GList* update_list; //< the descendants that need Update() called - void AddModelName( StgModel* mod ); void StartUpdatingModel( StgModel* mod ); void StopUpdatingModel( StgModel* mod ); @@ -1055,9 +1064,10 @@ void RemoveBlock( int x, int y, StgBlock* block ); -protected: +public: stg_usec_t interval_real; ///< real-time interval between updates - set this to zero for 'as fast as possible +protected: GHashTable* superregions; static void UpdateCb( StgWorld* world); @@ -1099,8 +1109,8 @@ stg_usec_t SimTimeNow(void){ return sim_time;} ; stg_usec_t RealTimeNow(void); stg_usec_t RealTimeSinceStart(void); - void PauseUntilNextUpdateTime(void); - void IdleUntilNextUpdateTime( int (*idler)(void) ); + //void PauseUntilNextUpdateTime(void); + // void IdleUntilNextUpdateTime( int (*idler)(void) ); void AddBlock( StgBlock* block ); void RemoveBlock( StgBlock* block ); @@ -1130,7 +1140,7 @@ /** Returns a pointer to the model identified by ID, or NULL if nonexistent */ - StgModel* GetModel( const stg_id_t id ); + //StgModel* GetModel( const stg_id_t id ); /** Returns a pointer to the model identified by name, or NULL if nonexistent */ @@ -1176,7 +1186,15 @@ static uint32_t count; static GHashTable* modelsbyid; + public: + + /** Look up a model pointer by a unique model ID */ + static StgModel* LookupId( uint32_t id ) + { + return (StgModel*)g_hash_table_lookup( modelsbyid, (void*)id ); + } + /** unique process-wide identifier for this model */ uint32_t id; @@ -1804,8 +1822,6 @@ // FLTK Gui includes #include <FL/Fl.H> -//#include <FL/Fl_Box.H> -//#include <FL/Fl_Double_Window.H> #include <FL/Fl_Gl_Window.H> #include <FL/Fl_Menu_Bar.H> #include <FL/Fl_Menu_Button.H> @@ -2003,15 +2019,13 @@ StgCanvas* canvas; Fl_Menu_Bar* mbar; + stg_usec_t real_time_of_last_update; + public: StgWorldGui(int W,int H,const char*L=0); ~StgWorldGui(); - /** Start the simulation and GUI. Does not return */ - static void Run(); - void Start(); - void Stop(); - void Cycle(); + virtual bool Update(); virtual void Load( const char* filename ); virtual void UnLoad(); @@ -2169,6 +2183,18 @@ 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/test.cc =================================================================== --- code/stage/trunk/libstage/test.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/test.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -8,8 +8,10 @@ void interact( StgWorldGui* wg ) { - for( int i=0; i<100; i++ ) - wg->Cycle(); + //for( int i=0; i<100; i++ ) + // wg->Cycle(); + + wg->Update(); } void test( char* str, double a, double b ) @@ -180,5 +182,6 @@ // } - StgWorldGui::Run(); + while(true) + world.Update(); } Modified: code/stage/trunk/libstage/world.cc =================================================================== --- code/stage/trunk/libstage/world.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/world.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -57,6 +57,7 @@ // static data members unsigned int StgWorld::next_id = 0; bool StgWorld::quit_all = false; +GList* StgWorld::world_list = NULL; static guint PointIntHash( stg_point_int_t* pt ) { @@ -84,6 +85,14 @@ delete sr; } +void StgWorld::UpdateAll() +{ + assert( StgWorld::world_list ); + + for( GList* it = StgWorld::world_list; it; it=it->next ) + ((StgWorld*)it->data)->Update(); +} + StgWorld::StgWorld( const char* token, stg_msec_t interval_sim, stg_msec_t interval_real, @@ -102,8 +111,8 @@ PRINT_WARN( "Stg::Init() must be called before a StgWorld is created." ); exit(-1); } - - // this->id = StgWorld::next_id++; + StgWorld::world_list = g_list_append( StgWorld::world_list, this ); + this->ray_list = NULL; this->quit_time = 0; @@ -159,6 +168,8 @@ g_hash_table_destroy( models_by_name ); g_free( token ); + + world_list = g_list_remove( world_list, this ); } @@ -399,54 +410,6 @@ return timenow - real_time_start; } -void StgWorld::PauseUntilNextUpdateTime( void ) -{ - // sleep until it's time to update - stg_usec_t timenow = RealTimeSinceStart(); - - /* printf( "\ntimesincestart %llu interval_real %llu interval_sim %llu real_time_next_update %llu\n", - timenow, - interval_real, - interval_sim, - real_time_next_update ); - */ - - if( timenow < real_time_next_update ) - { - usleep( real_time_next_update - timenow ); - } - - interval_log[updates%INTERVAL_LOG_LEN] = timenow - real_time_now; - - real_time_now = timenow; - real_time_next_update += interval_real; -} - -void StgWorld::IdleUntilNextUpdateTime( int (*idler)(void) ) -{ - // sleep until it's time to update - stg_usec_t timenow; - - /* printf( "\ntimesincestart %llu interval_real %llu interval_sim %llu real_time_next_update %llu\n", - timenow, - interval_real, - interval_sim, - real_time_next_update ); - */ - - while( (timenow = RealTimeSinceStart()) < real_time_next_update ) - { - (*idler)(); - usleep( 1000 ); - } - - interval_log[updates%INTERVAL_LOG_LEN] = timenow - real_time_now; - - real_time_now = timenow; - real_time_next_update += interval_real; -} - - #define DEBUG 1 bool StgWorld::Update() @@ -474,27 +437,13 @@ stg_usec_t timenow = RealTimeSinceStart(); interval_log[updates%INTERVAL_LOG_LEN] = timenow - real_time_now; - - //interval_log[updates%INTERVAL_LOG_LEN] = timenow - real_time_now; - real_time_now = timenow; - //real_time_next_update += interval_real; return true; } void StgWorld::AddModel( StgModel* mod ) { - //PRINT_DEBUG3( "World %s adding model %d %s to hash tables ", - // token, mod->id, mod->Token() ); - - //g_hash_table_insert( this->models_by_id, (gpointer)mod->Id(), mod ); - AddModelName( mod ); -} - - -void StgWorld::AddModelName( StgModel* mod ) -{ g_hash_table_insert( this->models_by_name, (gpointer)mod->Token(), mod ); } @@ -509,13 +458,6 @@ return mod; } -// StgModel* StgWorld::GetModel( const stg_id_t id ) -// { -// PRINT_DEBUG1( "looking up model id %d in models_by_id", id ); -// return (StgModel*)g_hash_table_lookup( this->models_by_id, (gpointer)id ); -// } - - void StgWorld::RecordRay( double x1, double y1, double x2, double y2 ) { float* drawpts = new float[4]; Modified: code/stage/trunk/libstage/worldgui.cc =================================================================== --- code/stage/trunk/libstage/worldgui.cc 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/libstage/worldgui.cc 2008-06-17 03:24:37 UTC (rev 6614) @@ -511,50 +511,38 @@ return StgWorld::Save( filename ); } -void StgWorld::UpdateCb( StgWorld* world ) -{ - world->Update(); - // need to reinstantiatethe timeout each time - Fl::repeat_timeout( world->interval_real/1e6, - (Fl_Timeout_Handler)UpdateCb, world ); -} - -static void idle_callback( StgWorld* world ) +bool StgWorldGui::Update() { - world->Update(); -} + if( real_time_of_last_update == 0 ) + real_time_of_last_update = RealTimeNow(); + + bool val = StgWorld::Update(); + + stg_usec_t interval; + stg_usec_t timenow; + + do { // we loop over updating the GUI, sleeping if there's any spare + // time + Fl::check(); -void StgWorldGui::Start() -{ - // if a non-zero interval was requested, call Update() after that - // interval - if( interval_real > 0 ) - Fl::add_timeout( interval_real/1e6, (Fl_Timeout_Handler)UpdateCb, this ); - else // otherwise call Update() whenever there's no GUI work to do - Fl::add_idle( (Fl_Timeout_Handler)idle_callback, this ); + timenow = RealTimeNow(); + interval = timenow - real_time_of_last_update; // guaranteed to be >= 0 + + double sleeptime = (double)interval_real - (double)interval; + + if( sleeptime > 0 ) + usleep( MIN(sleeptime,100000) ); // check the GUI at 10Hz min + + } while( interval < interval_real ); + + + real_time_of_last_update = timenow; + + return val; } -void StgWorldGui::Stop() -{ - Fl::remove_timeout( (Fl_Timeout_Handler)UpdateCb, this ); - Fl::remove_idle( (Fl_Timeout_Handler)idle_callback, this ); -} - - -void StgWorldGui::Run() -{ - Fl::run(); -} - -void StgWorldGui::Cycle() -{ - if( Fl::ready() ) - Fl::check(); -} - - void StgWorldGui::DrawTree( bool drawall ) { g_hash_table_foreach( superregions, (GHFunc)SuperRegion::Draw_cb, NULL ); Modified: code/stage/trunk/worlds/fasr.world =================================================================== --- code/stage/trunk/worlds/fasr.world 2008-06-17 03:08:57 UTC (rev 6613) +++ code/stage/trunk/worlds/fasr.world 2008-06-17 03:24:37 UTC (rev 6614) @@ -15,7 +15,7 @@ resolution 0.02 interval_sim 100 # simulation timestep in milliseconds -interval_real 0 # real-time interval between simulation updates in milliseconds +interval_real 20 # real-time interval between simulation updates in milliseconds paused 1 # configure the GUI window @@ -26,7 +26,7 @@ rotate [ 0.000 0.000 ] scale 33.306 show_data 0 - interval 100 + #interval 10 ) # load an environment bitmap 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 Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit