Revision: 6617 http://playerstage.svn.sourceforge.net/playerstage/?rev=6617&view=rev Author: rtv Date: 2008-06-17 00:40:18 -0700 (Tue, 17 Jun 2008)
Log Message: ----------- cleaning up API some more - moved real time stuff out of world and into worldgui where it belongs Modified Paths: -------------- code/stage/trunk/CMakeLists.txt code/stage/trunk/docsrc/stage.dox code/stage/trunk/docsrc/stage.txt code/stage/trunk/libstage/CMakeLists.txt code/stage/trunk/libstage/canvas.cc code/stage/trunk/libstage/stage.hh code/stage/trunk/libstage/world.cc code/stage/trunk/libstage/worldgui.cc code/stage/trunk/libstageplugin/CMakeLists.txt code/stage/trunk/libstageplugin/p_driver.cc code/stage/trunk/libstageplugin/p_driver.h code/stage/trunk/libstageplugin/p_graphics3d.cc code/stage/trunk/libstageplugin/p_laser.cc code/stage/trunk/libstageplugin/p_position.cc code/stage/trunk/libstageplugin/p_sonar.cc code/stage/trunk/worlds/fasr.world code/stage/trunk/worlds/simple.world Modified: code/stage/trunk/CMakeLists.txt =================================================================== --- code/stage/trunk/CMakeLists.txt 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/CMakeLists.txt 2008-06-17 07:40:18 UTC (rev 6617) @@ -8,13 +8,8 @@ SET( APIVERSION ${V_MAJOR}.${V_MINOR} ) # minimum version of Player to build the plugin -SET( MIN_PLAYER 99.0.0 ) # change once plugin is fixed +SET( MIN_PLAYER 2.2.0 ) # change once plugin is fixed -#SET(CMAKE_BUILD_TYPE debug) -#SET(CMAKE_CXX_FLAGS_DISTRIBUTION "-O3") -#SET(CMAKE_C_FLAGS_DISTRIBUTION "-O3") - - cmake_minimum_required( VERSION 2.4 FATAL_ERROR ) IF (CMAKE_MAJOR_VERSION EQUAL 2 AND NOT CMAKE_MINOR_VERSION LESS 6) @@ -35,23 +30,9 @@ pkg_search_module( GLIB REQUIRED glib-2.0 ) find_package( OpenGL REQUIRED ) -# Look for player v${MIN_PLAYER} or higher and set flags -# built-ins don't work properly, so use pkg-config directly -FIND_PROGRAM (PKGCONFIG NAMES pkg-config) -IF (PKGCONFIG) - EXECUTE_PROCESS (COMMAND pkg-config --atleast-version=${MIN_PLAYER} playercore --silence-errors - RESULT_VARIABLE PLAYER_FOUND) - IF (PLAYER_FOUND EQUAL 0) - # found the correct version - pkg_search_module( PLAYER playercore ) - ADD_SUBDIRECTORY( libstageplugin ) - ELSE (PLAYER_FOUND EQUAL 0) - MESSAGE(STATUS "Player >=v${MIN_PLAYER} not found, skipping Player plugin") - ENDIF (PLAYER_FOUND EQUAL 0) -ELSE (PKGCONFIG) - MESSAGE (STATUS "pkg-config not found, skipping Player plugin") -ENDIF (PKGCONFIG) +pkg_search_module( PLAYER playercore ) + # find FLTK and set flags FIND_PROGRAM (FLTKCONFIG NAMES fltk-config) IF (FLTKCONFIG) @@ -99,6 +80,11 @@ ADD_SUBDIRECTORY(libstage) ADD_SUBDIRECTORY(examples) +if( PLAYER_FOUND ) +ADD_SUBDIRECTORY(libstageplugin) +endif( PLAYER_FOUND ) + + INSTALL(FILES rgb.txt stagelogo.png DESTINATION share/stage ) Modified: code/stage/trunk/docsrc/stage.dox =================================================================== --- code/stage/trunk/docsrc/stage.dox 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/docsrc/stage.dox 2008-06-17 07:40:18 UTC (rev 6617) @@ -159,7 +159,7 @@ # member inherits the documentation from any documented member that it # re-implements. -INHERIT_DOCS = NO +INHERIT_DOCS = YES # If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC # tag is set to YES, then doxygen will reuse the documentation of the first @@ -219,7 +219,7 @@ # Private class members and static file members will be hidden unless # the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES -EXTRACT_ALL = YES +EXTRACT_ALL = NO # If the EXTRACT_PRIVATE tag is set to YES all private members of a class # will be included in the documentation. @@ -569,13 +569,13 @@ # then for each documented function all documented # functions referencing it will be listed. -REFERENCED_BY_RELATION = YES +REFERENCED_BY_RELATION = NO # If the REFERENCES_RELATION tag is set to YES (the default) # then for each documented function all documented entities # called/used by that function will be listed. -REFERENCES_RELATION = YES +REFERENCES_RELATION = NO # If the USE_HTAGS tag is set to YES then the references to source code # will point to the HTML generated by the htags(1) tool instead of doxygen Modified: code/stage/trunk/docsrc/stage.txt =================================================================== --- code/stage/trunk/docsrc/stage.txt 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/docsrc/stage.txt 2008-06-17 07:40:18 UTC (rev 6617) @@ -85,6 +85,8 @@ <li>Reed Hedges <tt>([EMAIL PROTECTED])</tt> <li>Andrew Howard <tt>([EMAIL PROTECTED])</tt> <li>Pooya Karimian <tt>([EMAIL PROTECTED])</tt> +<li>Jeremy Asher <tt>([EMAIL PROTECTED])</tt> +<li>Alex Couture-Beil <tt>([EMAIL PROTECTED])</tt> </ul> Many patches and bug reports have been contributed by users around the Modified: code/stage/trunk/libstage/CMakeLists.txt =================================================================== --- code/stage/trunk/libstage/CMakeLists.txt 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstage/CMakeLists.txt 2008-06-17 07:40:18 UTC (rev 6617) @@ -1,5 +1,8 @@ add_library( stage SHARED + world.cc + worldgui.cc + worldfile.cc stage.cc typetable.cc stage.hh # get headers into IDE projects @@ -23,9 +26,6 @@ model_props.cc model_ranger.cc resource.cc - world.cc - worldfile.cc - worldgui.cc texture_manager.cc ) Modified: code/stage/trunk/libstage/canvas.cc =================================================================== --- code/stage/trunk/libstage/canvas.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstage/canvas.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -21,7 +21,7 @@ } - StgCanvas::StgCanvas( StgWorld* world, int x, int y, int w, int h) + StgCanvas::StgCanvas( StgWorldGui* world, int x, int y, int w, int h) : Fl_Gl_Window(x,y,w,h) { end(); @@ -88,7 +88,7 @@ // render all top-level, draggable models in a color that is their // id - for( GList* it=world->children; it; it=it->next ) + for( GList* it= world->StgWorld::children; it; it=it->next ) { StgModel* mod = (StgModel*)it->data; @@ -444,7 +444,7 @@ glDisable( GL_DEPTH_TEST ); glPolygonMode(GL_FRONT_AND_BACK, GL_FILL ); - for( GList* it=world->children; it; it=it->next ) + for( GList* it=world->StgWorld::children; it; it=it->next ) { ((StgModel*)it->data)->DrawTrailFootprint(); } @@ -455,7 +455,7 @@ { glPolygonMode(GL_FRONT_AND_BACK, GL_FILL ); - for( GList* it=world->children; it; it=it->next ) + for( GList* it=world->StgWorld::children; it; it=it->next ) { ((StgModel*)it->data)->DrawTrailBlocks(); } @@ -464,7 +464,7 @@ if( showflags & STG_SHOW_ARROWS ) { glEnable( GL_DEPTH_TEST ); - for( GList* it=world->children; it; it=it->next ) + for( GList* it=world->StgWorld::children; it; it=it->next ) { ((StgModel*)it->data)->DrawTrailArrows(); } @@ -472,7 +472,7 @@ if( showflags & STG_SHOW_BLOCKS ) { - for( GList* it=world->children; it; it=it->next ) + for( GList* it=world->StgWorld::children; it; it=it->next ) { StgModel* mod = ((StgModel*)it->data); @@ -500,7 +500,7 @@ //mod->Draw( showflags ); // draw the stuff that changes every update // draw everything else - for( GList* it=world->children; it; it=it->next ) + for( GList* it=world->StgWorld::children; it; it=it->next ) ((StgModel*)it->data)->Draw( showflags, this ); } Modified: code/stage/trunk/libstage/stage.hh =================================================================== --- code/stage/trunk/libstage/stage.hh 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstage/stage.hh 2008-06-17 07:40:18 UTC (rev 6617) @@ -988,7 +988,7 @@ static int AddBlockPixel( int x, int y, int z, stg_render_info_t* rinfo ) ; //< used as a callback by StgModel - stg_usec_t real_time_next_update; + //stg_usec_t real_time_next_update; stg_usec_t real_time_start; bool quit; // quit this world ASAP @@ -996,11 +996,10 @@ // convert a distance in meters to a distance in world occupancy grid pixels int32_t MetersToPixels( stg_meters_t x ){ return (int32_t)floor(x * ppm) ; }; - void Initialize( const char* token, - stg_msec_t interval_sim, - stg_msec_t interval_real, - double ppm ); - + void Initialize( const char* token, + stg_msec_t interval_sim, + double ppm ); + 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 */ }; @@ -1018,23 +1017,14 @@ GHashTable* models_by_name; ///< the models that make up the world, indexed by name 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 - long unsigned int updates; ///< the number of simulated time steps executed so far - bool dirty; ///< iff true, a gui redraw would be required - stg_usec_t interval_sim; ///< temporal resolution: milliseconds that elapse between simulated time steps - stg_usec_t interval_log[INTERVAL_LOG_LEN]; - int total_subs; ///< the total number of subscriptions to all models double ppm; ///< the resolution of the world model in pixels per meter - bool paused; ///< the world only updates when this is false - GList* update_list; //< the descendants that need Update() called void StartUpdatingModel( StgModel* mod ); @@ -1063,14 +1053,13 @@ void RemoveBlock( int x, int y, StgBlock* block ); - -public: - stg_usec_t interval_real; ///< real-time interval between updates - set this to zero for 'as fast as possible - protected: GHashTable* superregions; + stg_usec_t interval_sim; ///< temporal resolution: milliseconds that elapse between simulated time steps static void UpdateCb( StgWorld* world); + + stg_usec_t sim_time; ///< the current sim time in this world in ms GList* ray_list; // store rays traced for debugging purposes @@ -1091,15 +1080,14 @@ GList* GetRayList(){ return ray_list; }; void ClearRays(); + long unsigned int updates; ///< the number of simulated time steps executed so far public: static const int DEFAULT_PPM = 50; // default resolution in pixels per meter - static const stg_msec_t DEFAULT_INTERVAL_REAL = 100; ///< real time between updates static const stg_msec_t DEFAULT_INTERVAL_SIM = 100; ///< duration of sim timestep StgWorld( const char* token = "MyWorld", stg_msec_t interval_sim = DEFAULT_INTERVAL_SIM, - stg_msec_t interval_real = DEFAULT_INTERVAL_REAL, double ppm = DEFAULT_PPM ); virtual ~StgWorld(); @@ -1125,9 +1113,6 @@ virtual bool Save( const char* filename ); virtual bool Update(void); - void Start(){ paused = false; }; - void Stop(){ paused = true; }; - void TogglePause(){ paused = !paused; }; bool TestQuit(){ return( quit || quit_all ); } void Quit(){ quit = true; } void QuitAll(){ quit_all = true; } @@ -1146,11 +1131,6 @@ nonexistent */ StgModel* GetModel( const char* name ); - - /** Get human readable string that describes the current simulation - time. */ - void ClockString( char* str, size_t maxlen ); - /** Return the 3D bounding box of the world, in meters */ stg_bounds3d_t GetExtent(){ return extent; }; @@ -1969,11 +1949,12 @@ void DrawGlobalGrid(); public: - StgCanvas( StgWorld* world, int x, int y, int W,int H); + + StgCanvas( StgWorldGui* world, int x, int y, int W,int H); ~StgCanvas(); bool graphics; - StgWorld* world; + StgWorldGui* world; void FixViewport(int W,int H); //robot_camera = true @@ -2005,48 +1986,62 @@ }; - - /** Extends StgWorld to implements an FLTK / OpenGL graphical user interface. */ class StgWorldGui : public StgWorld, public Fl_Window { - friend class StgCanvas; - - private: - int wf_section; - StgCanvas* canvas; - Fl_Menu_Bar* mbar; - + friend class StgCanvas; + friend class StgModelCamera; + +private: + bool paused; ///< the world only updates when this is false + //int wf_section; + StgCanvas* canvas; + Fl_Menu_Bar* mbar; + stg_usec_t interval_log[INTERVAL_LOG_LEN]; + 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 - public: - StgWorldGui(int W,int H,const char*L=0); - ~StgWorldGui(); +public: + static const stg_msec_t DEFAULT_INTERVAL_REAL = 100; ///< real time between updates + StgWorldGui(int W,int H,const char*L=0); + ~StgWorldGui(); + virtual bool Update(); - - virtual void Load( const char* filename ); - virtual void UnLoad(); - virtual bool Save( const char* filename ); + virtual void Load( const char* filename ); + virtual void UnLoad(); + virtual bool Save( const char* filename ); + + + void Start(){ paused = false; }; + void Stop(){ paused = true; }; + void TogglePause(){ paused = !paused; }; + + /** Get human readable string that describes the current simulation + time. */ + void ClockString( char* str, size_t maxlen ); + /** Set the minimum real time interval between world updates, in microeconds. */ void SetRealTimeInterval( stg_usec_t usec ) { interval_real = usec; } - - // static callback functions - static void LoadCallback( Fl_Widget* wid, StgWorldGui* world ); - static void SaveCallback( Fl_Widget* wid, StgWorldGui* world ); - static void SaveAsCallback( Fl_Widget* wid, StgWorldGui* world ); - static void QuitCallback( Fl_Widget* wid, StgWorldGui* world ); - static void About_cb( Fl_Widget* wid, StgWorldGui* world ); - static void HelpAboutCallback( Fl_Widget* wid ); - static void view_toggle_cb( Fl_Menu_Bar* menubar, StgCanvas* canvas ); - static void WindowCallback( Fl_Widget* wid, StgWorldGui* world ); - + + // static callback functions +protected: + static void LoadCallback( Fl_Widget* wid, StgWorldGui* world ); + static void SaveCallback( Fl_Widget* wid, StgWorldGui* world ); + static void SaveAsCallback( Fl_Widget* wid, StgWorldGui* world ); + static void QuitCallback( Fl_Widget* wid, StgWorldGui* world ); + static void About_cb( Fl_Widget* wid, StgWorldGui* world ); + static void HelpAboutCallback( Fl_Widget* wid ); + static void view_toggle_cb( Fl_Menu_Bar* menubar, StgCanvas* canvas ); + static void WindowCallback( Fl_Widget* wid, StgWorldGui* world ); + bool SaveAsDialog(); bool CloseWindowQuery(); Modified: code/stage/trunk/libstage/world.cc =================================================================== --- code/stage/trunk/libstage/world.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstage/world.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -95,15 +95,13 @@ StgWorld::StgWorld( const char* token, stg_msec_t interval_sim, - stg_msec_t interval_real, double ppm ) { - Initialize( token, interval_sim, interval_real, ppm ); + Initialize( token, interval_sim, ppm ); } void StgWorld::Initialize( const char* token, stg_msec_t interval_sim, - stg_msec_t interval_real, double ppm ) { if( ! Stg::InitDone() ) @@ -130,11 +128,10 @@ this->models_by_name = g_hash_table_new( g_str_hash, g_str_equal ); this->sim_time = 0; this->interval_sim = (stg_usec_t)thousand * interval_sim; - this->interval_real = (stg_usec_t)thousand * interval_real; this->ppm = ppm; // this is the raytrace resolution this->real_time_start = RealTimeNow(); - this->real_time_next_update = 0; + //this->real_time_next_update = 0; this->update_list = NULL; this->velocity_list = NULL; @@ -143,7 +140,6 @@ (GEqualFunc)PointIntEqual ); this->total_subs = 0; - this->paused = false; this->destroy = false; // store a global table of all blocks, so they can be rendered all @@ -152,8 +148,6 @@ bzero( &this->extent, sizeof(this->extent)); - for( unsigned int i=0; i<INTERVAL_LOG_LEN; i++ ) - this->interval_log[i] = this->interval_real; this->real_time_now = 0; } @@ -179,53 +173,7 @@ g_hash_table_remove( models_by_name, mod ); } -void StgWorld::ClockString( char* str, size_t maxlen ) -{ - const uint32_t usec_per_hour = 360000000; - const uint32_t usec_per_minute = 60000000; - const uint32_t usec_per_second = 1000000; - const uint32_t usec_per_msec = 1000; - uint32_t hours = sim_time / usec_per_hour; - uint32_t minutes = (sim_time % usec_per_hour) / usec_per_minute; - uint32_t seconds = (sim_time % usec_per_minute) / usec_per_second; - uint32_t msec = (sim_time % usec_per_second) / usec_per_msec; - - // find the average length of the last few realtime intervals; - stg_usec_t average_real_interval = 0; - for( uint32_t i=0; i<INTERVAL_LOG_LEN; i++ ) - average_real_interval += interval_log[i]; - average_real_interval /= INTERVAL_LOG_LEN; - - double localratio = (double)interval_sim / (double)average_real_interval; - -#ifdef DEBUG - if( hours > 0 ) - snprintf( str, maxlen, "Time: %uh%02um%02u.%03us\t[%.6f]\tsubs: %d %s", - hours, minutes, seconds, msec, - localratio, - total_subs, - paused ? "--PAUSED--" : "" ); - else - snprintf( str, maxlen, "Time: %02um%02u.%03us\t[%.6f]\tsubs: %d %s", - minutes, seconds, msec, - localratio, - total_subs, - paused ? "--PAUSED--" : "" ); -#else - if( hours > 0 ) - snprintf( str, maxlen, "%uh%02um%02u.%03us\t[%.2f] %s", - hours, minutes, seconds, msec, - localratio, - paused ? "--PAUSED--" : "" ); - else - snprintf( str, maxlen, "%02um%02u.%03us\t[%.2f] %s", - minutes, seconds, msec, - localratio, - paused ? "--PAUSED--" : "" ); -#endif -} - // wrapper to startup all models from the hash table void init_models( gpointer dummy1, StgModel* mod, gpointer dummy2 ) { @@ -266,9 +214,6 @@ this->token = (char*) wf->ReadString( entity, "name", token ); - this->interval_real = (stg_usec_t)thousand * - wf->ReadInt( entity, "interval_real", this->interval_real/thousand ); - this->interval_sim = (stg_usec_t)thousand * wf->ReadInt( entity, "interval_sim", this->interval_sim/thousand ); @@ -280,9 +225,6 @@ this->ppm = 1.0 / wf->ReadFloat( entity, "resolution", 1.0 / this->ppm ); - this->paused = - wf->ReadInt( entity, "paused", this->paused ); - //_stg_disable_gui = wf->ReadInt( entity, "gui_disable", _stg_disable_gui ); // Iterate through entitys and create client-side models @@ -414,32 +356,24 @@ bool StgWorld::Update() { - PRINT_DEBUG( "StgWorld::Update()" ); + PRINT_DEBUG( "StgWorld::Update()" ); + + // update any models that are due to be updated + for( GList* it=this->update_list; it; it=it->next ) + ((StgModel*)it->data)->UpdateIfDue(); + + // update any models with non-zero velocity + for( GList* it=this->velocity_list; it; it=it->next ) + ((StgModel*)it->data)->UpdatePose(); - if( paused ) - return false; - - // update any models that are due to be updated - for( GList* it=this->update_list; it; it=it->next ) - ((StgModel*)it->data)->UpdateIfDue(); - - // update any models with non-zero velocity - for( GList* it=this->velocity_list; it; it=it->next ) - ((StgModel*)it->data)->UpdatePose(); - - 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; - - stg_usec_t timenow = RealTimeSinceStart(); - - interval_log[updates%INTERVAL_LOG_LEN] = timenow - real_time_now; - real_time_now = timenow; - - return true; + 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; } void StgWorld::AddModel( StgModel* mod ) Modified: code/stage/trunk/libstage/worldgui.cc =================================================================== --- code/stage/trunk/libstage/worldgui.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstage/worldgui.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -134,7 +134,13 @@ //size_range( 100,100 ); // set minimum window size graphics = true; + paused = false; + interval_real = (stg_usec_t)thousand * DEFAULT_INTERVAL_REAL; + + for( unsigned int i=0; i<INTERVAL_LOG_LEN; i++ ) + this->interval_log[i] = this->interval_real; + // build the menus mbar = new Fl_Menu_Bar(0,0, W, 30);// 640, 30); mbar->textsize(12); @@ -191,16 +197,73 @@ delete canvas; } + +void StgWorldGui::ClockString( char* str, size_t maxlen ) +{ + const uint32_t usec_per_hour = 360000000; + const uint32_t usec_per_minute = 60000000; + const uint32_t usec_per_second = 1000000; + const uint32_t usec_per_msec = 1000; + + uint32_t hours = sim_time / usec_per_hour; + uint32_t minutes = (sim_time % usec_per_hour) / usec_per_minute; + uint32_t seconds = (sim_time % usec_per_minute) / usec_per_second; + uint32_t msec = (sim_time % usec_per_second) / usec_per_msec; + + // find the average length of the last few realtime intervals; + stg_usec_t average_real_interval = 0; + for( uint32_t i=0; i<INTERVAL_LOG_LEN; i++ ) + average_real_interval += interval_log[i]; + average_real_interval /= INTERVAL_LOG_LEN; + + double localratio = (double)interval_sim / (double)average_real_interval; + +#ifdef DEBUG + if( hours > 0 ) + snprintf( str, maxlen, "Time: %uh%02um%02u.%03us\t[%.6f]\tsubs: %d %s", + hours, minutes, seconds, msec, + localratio, + total_subs, + paused ? "--PAUSED--" : "" ); + else + snprintf( str, maxlen, "Time: %02um%02u.%03us\t[%.6f]\tsubs: %d %s", + minutes, seconds, msec, + localratio, + total_subs, + paused ? "--PAUSED--" : "" ); +#else + if( hours > 0 ) + snprintf( str, maxlen, "%uh%02um%02u.%03us\t[%.2f] %s", + hours, minutes, seconds, msec, + localratio, + paused ? "--PAUSED--" : "" ); + else + snprintf( str, maxlen, "%02um%02u.%03us\t[%.2f] %s", + minutes, seconds, msec, + localratio, + paused ? "--PAUSED--" : "" ); +#endif +} + + void StgWorldGui::Load( const char* filename ) { PRINT_DEBUG1( "%s.Load()", token ); StgWorld::Load( filename ); - wf_section = wf->LookupEntity( "window" ); - if( wf_section < 1) // no section defined - return; +// wf_section = wf->LookupEntity( "window" ); +// if( wf_section < 1) // no section defined +// return; + + int wf_section = 0; // root section + this->paused = + wf->ReadInt( wf_section, "paused", this->paused ); + + this->interval_real = (stg_usec_t)thousand * + wf->ReadInt( wf_section, "interval_real", this->interval_real/thousand ); + int width = (int)wf->ReadTupleFloat(wf_section, "size", 0, w() ); int height = (int)wf->ReadTupleFloat(wf_section, "size", 1, h() ); // on OS X this behaves badly - prevents the Window manager resizing @@ -486,6 +549,8 @@ { PRINT_DEBUG1( "%s.Save()", token ); + int wf_section = 0; + wf->WriteTupleFloat( wf_section, "size", 0, w() ); wf->WriteTupleFloat( wf_section, "size", 1, h() ); @@ -516,10 +581,9 @@ { if( real_time_of_last_update == 0 ) real_time_of_last_update = RealTimeNow(); + + bool val = paused ? true : StgWorld::Update(); - bool val = StgWorld::Update(); - - stg_usec_t interval; stg_usec_t timenow; @@ -540,6 +604,12 @@ real_time_of_last_update = timenow; + //stg_usec_t timenow = RealTimeSinceStart(); + + interval_log[updates%INTERVAL_LOG_LEN] = interval_real;//timenow - real_time_now; + // real_time_now = timenow; + + return val; } Modified: code/stage/trunk/libstageplugin/CMakeLists.txt =================================================================== --- code/stage/trunk/libstageplugin/CMakeLists.txt 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/CMakeLists.txt 2008-06-17 07:40:18 UTC (rev 6617) @@ -1,6 +1,7 @@ link_directories( ${PLAYER_LIBDIR} ) include_directories( ${PLAYER_INCLUDE_DIRS}) +message( PLAYER INCLUDE ${PLAYER_INCLUDE_DIRS} ) add_library( stageplugin MODULE p_driver.cc Modified: code/stage/trunk/libstageplugin/p_driver.cc =================================================================== --- code/stage/trunk/libstageplugin/p_driver.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/p_driver.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -225,10 +225,10 @@ } InterfaceModel::InterfaceModel( player_devaddr_t addr, - StgDriver* driver, - ConfigFile* cf, - int section, - char* typestr ) + StgDriver* driver, + ConfigFile* cf, + int section, + stg_model_type_t type ) : Interface( addr, driver, cf, section ) { char* model_name = (char*)cf->ReadString(section, "model", NULL ); @@ -246,7 +246,7 @@ // find a model of the right type this->mod = driver->LocateModel( model_name, &addr, - typestr ); + type ); if( !this->mod ) { @@ -407,30 +407,30 @@ StgModel* StgDriver::LocateModel( char* basename, player_devaddr_t* addr, - char* typestr ) + stg_model_type_t type ) { - printf( "attempting to find a model under model \"%s\" of type [%s]\n", - basename, typestr ); + printf( "attempting to find a model under model \"%s\" of type [%d]\n", + basename, type ); StgModel* base_model = world->GetModel( basename ); if( base_model == NULL ) { PRINT_ERR1( " Error! can't find a Stage model named \"%s\"", - basename ); + basename ); return NULL; } - if( typestr == NULL ) // if we don't care what type the model is + if( type == MODEL_TYPE_PLAIN ) // if we don't care what type the model is return base_model; - + // printf( "found base model %s\n", base_model->Token() ); - + // we find the first model in the tree that is the right // type (i.e. has the right initialization function) and has not // been used before //return( model_match( base_model, addr, typestr, this->devices ) ); - return( base_model->GetUnsubscribedModelOfType( typestr ) ); + return( base_model->GetUnsubscribedModelOfType( type ) ); } //////////////////////////////////////////////////////////////////////////////// @@ -511,7 +511,7 @@ // Shutdown the device int StgDriver::Shutdown() { - puts("Shutting stage driver down"); + //puts("Shutting stage driver down"); // Stop and join the driver thread // this->StopThread(); // todo - the thread only runs in the sim instance @@ -523,7 +523,7 @@ // stg_model_unsubscribe( device->mod ); // } - puts("stage driver has been shutdown"); + puts("Stage driver has been shutdown"); return(0); } Modified: code/stage/trunk/libstageplugin/p_driver.h =================================================================== --- code/stage/trunk/libstageplugin/p_driver.h 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/p_driver.h 2008-06-17 07:40:18 UTC (rev 6617) @@ -45,7 +45,7 @@ StgModel* LocateModel( char* basename, player_devaddr_t* addr, - char* typestr); + stg_model_type_t type ); protected: @@ -100,7 +100,7 @@ StgDriver* driver, ConfigFile* cf, int section, - char* typestr ); + stg_model_type_t type ); StgModel* mod; Modified: code/stage/trunk/libstageplugin/p_graphics3d.cc =================================================================== --- code/stage/trunk/libstageplugin/p_graphics3d.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/p_graphics3d.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -58,7 +58,7 @@ StgDriver* driver, ConfigFile* cf, int section ) - : InterfaceModel( addr, driver, cf, section, NULL ) + : InterfaceModel( addr, driver, cf, section, MODEL_TYPE_PLAIN ) { // data members commands = NULL; Modified: code/stage/trunk/libstageplugin/p_laser.cc =================================================================== --- code/stage/trunk/libstageplugin/p_laser.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/p_laser.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -44,7 +44,7 @@ StgDriver* driver, ConfigFile* cf, int section ) - : InterfaceModel( addr, driver, cf, section, "laser" ) + : InterfaceModel( addr, driver, cf, section, MODEL_TYPE_LASER ) { this->scan_id = 0; } Modified: code/stage/trunk/libstageplugin/p_position.cc =================================================================== --- code/stage/trunk/libstageplugin/p_position.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/p_position.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -51,7 +51,7 @@ ConfigFile* cf, int section ) - : InterfaceModel( addr, driver, cf, section, "position" ) + : InterfaceModel( addr, driver, cf, section, MODEL_TYPE_POSITION ) { //puts( "InterfacePosition constructor" ); } Modified: code/stage/trunk/libstageplugin/p_sonar.cc =================================================================== --- code/stage/trunk/libstageplugin/p_sonar.cc 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/libstageplugin/p_sonar.cc 2008-06-17 07:40:18 UTC (rev 6617) @@ -46,7 +46,7 @@ StgDriver* driver, ConfigFile* cf, int section ) - : InterfaceModel( id, driver, cf, section, "ranger" ) + : InterfaceModel( id, driver, cf, section, MODEL_TYPE_RANGER ) { //this->data_len = sizeof(player_sonar_data_t); //this->cmd_len = 0; Modified: code/stage/trunk/worlds/fasr.world =================================================================== --- code/stage/trunk/worlds/fasr.world 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/worlds/fasr.world 2008-06-17 07:40:18 UTC (rev 6617) @@ -19,16 +19,13 @@ paused 1 # configure the GUI window -window -( - #size [ 698.000 628.000 ] - center [6.990 -4.040] - rotate [ 0.000 0.000 ] - scale 33.306 - show_data 0 - #interval 10 -) +size [ 698.000 628.000 ] +center [6.990 -4.040] +rotate [ 0.000 0.000 ] +scale 33.306 +show_data 0 + # load an environment bitmap floorplan ( Modified: code/stage/trunk/worlds/simple.world =================================================================== --- code/stage/trunk/worlds/simple.world 2008-06-17 03:43:58 UTC (rev 6616) +++ code/stage/trunk/worlds/simple.world 2008-06-17 07:40:18 UTC (rev 6617) @@ -20,23 +20,21 @@ paused 0 # configure the GUI window -window +size [ 745.000 448.000 ] +center [-7.010 5.960] +rotate [ 0.920 -0.430 ] +scale 28.806 + + +# load an environment bitmap +floorplan ( - size [ 745.000 448.000 ] - center [-7.010 5.960] - rotate [ 0.920 -0.430 ] - scale 28.806 + name "cave" + size3 [16 16 1.5] + pose [0.000 0.000 0.000] + bitmap "bitmaps/cave.png" ) -# load an environment bitmap -#floorplan -#( -# name "cave" -# size3 [16 16 0.5] -# pose [0.000 0.000 0.000] -# bitmap "bitmaps/cave.png" -#) - define autorob fancypioneer2dx ( color "red" 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