Revision: 6694
http://playerstage.svn.sourceforge.net/playerstage/?rev=6694&view=rev
Author: jeremy_asher
Date: 2008-06-26 13:29:42 -0700 (Thu, 26 Jun 2008)
Log Message:
-----------
Options interface implemented
Modified Paths:
--------------
code/stage/trunk/libstage/model.cc
code/stage/trunk/libstage/model_laser.cc
code/stage/trunk/libstage/option.hh
code/stage/trunk/libstage/options_dlg.cc
code/stage/trunk/libstage/options_dlg.hh
code/stage/trunk/libstage/stage.hh
code/stage/trunk/libstage/world.cc
code/stage/trunk/libstage/worldgui.cc
Modified: code/stage/trunk/libstage/model.cc
===================================================================
--- code/stage/trunk/libstage/model.cc 2008-06-26 20:10:49 UTC (rev 6693)
+++ code/stage/trunk/libstage/model.cc 2008-06-26 20:29:42 UTC (rev 6694)
@@ -139,7 +139,10 @@
// static members
uint32_t StgModel::count = 0;
-Option StgModel::ShowFlags( 0, "Show Flags", true );
+Option StgModel::ShowFlags( "Flags", true );
+Option StgModel::ShowVisData( "Sensor Visualizations", false );
+Option StgModel::ShowBlinken( "Show Blinkenlights", true );
+Option StgModel::ShowStatus( "Show Status", true );
GHashTable* StgModel::modelsbyid = g_hash_table_new( NULL, NULL );
@@ -168,10 +171,11 @@
// Adding this model to its ancestor also gives this model a
// sensible default name
-
- StgAncestor* anc = parent ? (StgAncestor*)parent : (StgAncestor*)world;
-
- anc->AddChild( this );
+ if ( parent )
+ parent->AddChild( this );
+ else
+ world->AddChild( this );
+
world->AddModel( this );
bzero( &pose, sizeof(pose));
@@ -889,6 +893,62 @@
}
+void StgModel::DrawStatus( StgCanvas* canvas ) {
+ // draw speech bubble
+ if( say_string )
+ {
+ float stheta = -dtor( canvas->camera.getPitch() );
+ float sphi = dtor( canvas->camera.getYaw() );
+ float scale = canvas->camera.getScale();
+
+ glPushMatrix();
+
+ // move above the robot
+ glTranslatef( 0, 0, 0.5 );
+
+ // rotate to face screen
+ glRotatef( -rtod(global_pose.a + sphi), 0,0,1 );
+ glRotatef( rtod(stheta), 1,0,0 );
+
+ const float m = 4 / scale; // margin
+ float w = gl_width( this->say_string ) / scale; // scaled text
width
+ float h = gl_height() / scale; // scaled text height
+
+
+ // draw inside of bubble
+ PushColor( BUBBLE_FILL );
+ glPushAttrib( GL_POLYGON_BIT | GL_LINE_BIT );
+ glPolygonMode( GL_FRONT, GL_FILL );
+ glEnable( GL_POLYGON_OFFSET_FILL );
+ glPolygonOffset( 1.0, 1.0 );
+ gl_draw_octagon( w, h, m );
+ glDisable( GL_POLYGON_OFFSET_FILL );
+ PopColor();
+ // draw outline of bubble
+ PushColor( BUBBLE_BORDER );
+ glLineWidth( 1 );
+ glEnable( GL_LINE_SMOOTH );
+ glPolygonMode( GL_FRONT, GL_LINE );
+ gl_draw_octagon( w, h, m );
+ glPopAttrib();
+ PopColor();
+
+
+ // draw text
+ PushColor( BUBBLE_TEXT );
+ glTranslatef( 0, 0, 0.1 ); // draw text forwards of bubble
+ gl_draw_string( m, m, 0.0, this->say_string );
+ PopColor();
+
+ glPopMatrix();
+ }
+
+ if( stall )
+ {
+ DrawImage( TextureManager::getInstance()._stall_texture_id,
canvas, 0.85 );
+ }
+}
+
void StgModel::DrawImage( uint32_t texture_id, Stg::StgCanvas* canvas, float
alpha )
{
float stheta = -dtor( canvas->camera.getPitch() );
@@ -937,73 +997,20 @@
- if( flags & STG_SHOW_DATA )
+ if( ShowVisData )
DataVisualize();
if( gui_grid && (flags & STG_SHOW_GRID) )
DrawGrid();
- if( flag_list )
+ if( ShowFlags )
DrawFlagList();
- if( blinkenlights )
+ if( ShowBlinken )
DrawBlinkenlights();
-
- if ( flags & STG_SHOW_STATUS ) {
- // draw speech bubble
- if( say_string )
- {
- float stheta = -dtor( canvas->camera.getPitch() );
- float sphi = dtor( canvas->camera.getYaw() );
- float scale = canvas->camera.getScale();
-
- glPushMatrix();
-
- // move above the robot
- glTranslatef( 0, 0, 0.5 );
-
- // rotate to face screen
- glRotatef( -rtod(global_pose.a + sphi), 0,0,1 );
- glRotatef( rtod(stheta), 1,0,0 );
-
- const float m = 4 / scale; // margin
- float w = gl_width( this->say_string ) / scale; //
scaled text width
- float h = gl_height() / scale; // scaled text height
-
-
- // draw inside of bubble
- PushColor( BUBBLE_FILL );
- glPushAttrib( GL_POLYGON_BIT | GL_LINE_BIT );
- glPolygonMode( GL_FRONT, GL_FILL );
- glEnable( GL_POLYGON_OFFSET_FILL );
- glPolygonOffset( 1.0, 1.0 );
- gl_draw_octagon( w, h, m );
- glDisable( GL_POLYGON_OFFSET_FILL );
- PopColor();
- // draw outline of bubble
- PushColor( BUBBLE_BORDER );
- glLineWidth( 1 );
- glEnable( GL_LINE_SMOOTH );
- glPolygonMode( GL_FRONT, GL_LINE );
- gl_draw_octagon( w, h, m );
- glPopAttrib();
- PopColor();
-
-
- // draw text
- PushColor( BUBBLE_TEXT );
- glTranslatef( 0, 0, 0.1 ); // draw text forwards of
bubble
- gl_draw_string( m, m, 0.0, this->say_string );
- PopColor();
-
- glPopMatrix();
- }
-
- if( stall )
- {
- DrawImage(
TextureManager::getInstance()._stall_texture_id, canvas, 0.85 );
- }
+ if ( ShowStatus ) {
+ DrawStatus( canvas );
}
// shift up the CS to the top of this model
@@ -1717,6 +1724,9 @@
const std::vector<Option*> StgModel::getOptions() {
std::vector<Option*> drawOptions;
drawOptions.push_back( &ShowFlags );
+ drawOptions.push_back( &ShowVisData );
+ drawOptions.push_back( &ShowBlinken );
+ drawOptions.push_back( &ShowStatus );
return drawOptions;
}
Modified: code/stage/trunk/libstage/model_laser.cc
===================================================================
--- code/stage/trunk/libstage/model_laser.cc 2008-06-26 20:10:49 UTC (rev
6693)
+++ code/stage/trunk/libstage/model_laser.cc 2008-06-26 20:29:42 UTC (rev
6694)
@@ -33,7 +33,7 @@
//const char COLOR[] = "steel blue";
//const char FILL_COLOR[] = "powder blue";
-Option StgModelLaser::ShowLaserData( 0, "Show Laser Data", false );
+Option StgModelLaser::ShowLaserData( "Show Laser Data", true );
/**
@ingroup model
@@ -297,6 +297,9 @@
void StgModelLaser::DataVisualize( void )
{
+ if ( !ShowLaserData )
+ return;
+
if( ! (samples && sample_count) )
return;
Modified: code/stage/trunk/libstage/option.hh
===================================================================
--- code/stage/trunk/libstage/option.hh 2008-06-26 20:10:49 UTC (rev 6693)
+++ code/stage/trunk/libstage/option.hh 2008-06-26 20:29:42 UTC (rev 6694)
@@ -7,19 +7,25 @@
class Option {
private:
- int index;
std::string optName;
bool value;
public:
Option() { }
- Option( int i, std::string n, bool v ) : index( i ), optName( n
), value( v ) { }
- Option( const Option& o ) : index( o.index ), optName(
o.optName ), value( o.value ) { }
+ Option( std::string n, bool v ) : optName( n ), value( v ) { }
+ Option( const Option& o ) : optName( o.optName ), value(
o.value ) { }
const std::string name() const { return optName; }
- const int id() const { return index; }
- const bool val() const { return value; }
+ inline const bool val() const { return value; }
+ inline operator bool() { return val(); }
+ inline bool operator<( const Option& rhs ) const
+ { return optName<rhs.optName; }
+ friend bool compare( const Option* lhs, const Option* rhs );
void set( bool val ) { value = val; }
};
-
+
+ struct optComp {
+ inline bool operator()( const Option* lhs, const Option* rhs )
const
+ { return lhs->operator<(*rhs); }
+ };
}
#endif
Modified: code/stage/trunk/libstage/options_dlg.cc
===================================================================
--- code/stage/trunk/libstage/options_dlg.cc 2008-06-26 20:10:49 UTC (rev
6693)
+++ code/stage/trunk/libstage/options_dlg.cc 2008-06-26 20:29:42 UTC (rev
6694)
@@ -5,6 +5,8 @@
OptionsDlg::OptionsDlg( int x, int y, int w, int h ) :
Fl_Window( /*x,y,*/w, h, "Model Options" ),
+ changedItem( NULL ),
+ status( NO_EVENT ),
hm( w/6 ) {
scroll = new Fl_Scroll( 0, 0, w, h-btnH-2*vm );
scroll->type( Fl_Scroll::VERTICAL );
@@ -26,16 +28,20 @@
OptionsDlg* oDlg = static_cast<OptionsDlg*>( p );
int item = oDlg->scroll->find( check );
- oDlg->options[ item ].set( check->value() );
+ oDlg->options[ item ]->set( check->value() );
oDlg->changedItem = oDlg->options[ item ];
+ oDlg->status = CHANGE;
oDlg->do_callback();
+ oDlg->changedItem = NULL;
+ oDlg->status = NO_EVENT;
}
void OptionsDlg::applyAllPress( Fl_Widget* w, void* p ) {
OptionsDlg* oDlg = static_cast<OptionsDlg*>( p );
- oDlg->changedItem = Option( -1, "", false );
+ oDlg->status = CHANGE_ALL;
oDlg->do_callback();
+ oDlg->status = NO_EVENT;
}
int OptionsDlg::handle( int event ) {
@@ -52,18 +58,24 @@
scroll->begin();
Fl_Check_Button* check;
for ( unsigned int i=0; i<options.size(); i++ ) {
- check = new Fl_Check_Button( 0,boxH*i, scroll->w(),
boxH, options[ i ].name().c_str() );
- if ( options[ i ].val() )
+ check = new Fl_Check_Button( 0,boxH*i, scroll->w(),
boxH, options[ i ]->name().c_str() );
+ if ( options[ i ]->val() )
check->set();
check->callback( checkChanged, this );
}
scroll->end();
}
- void OptionsDlg::setOptions( const std::vector<Option>& opts ) {
+ void OptionsDlg::setOptions( const std::vector<Option*>& opts ) {
options.clear();
options.insert( options.begin(), opts.begin(), opts.end() );
updateChecks();
}
+
+ void OptionsDlg::setOptions( const std::set<Option*, optComp>& opts ) {
+ options.clear();
+ options.insert( options.begin(), opts.begin(), opts.end() );
+ updateChecks();
+ }
} // namespace Stg
\ No newline at end of file
Modified: code/stage/trunk/libstage/options_dlg.hh
===================================================================
--- code/stage/trunk/libstage/options_dlg.hh 2008-06-26 20:10:49 UTC (rev
6693)
+++ code/stage/trunk/libstage/options_dlg.hh 2008-06-26 20:29:42 UTC (rev
6694)
@@ -8,15 +8,20 @@
#include <string>
#include <vector>
+#include <set>
#include "option.hh"
namespace Stg {
class OptionsDlg : protected Fl_Window {
+ public:
+ enum event_t { NO_EVENT, CHANGE, CHANGE_ALL };
+
private:
- std::vector<Option> options;
- Option changedItem;
+ std::vector<Option*> options;
+ Option* changedItem;
+ event_t status;
Fl_Scroll* scroll;
Fl_Button* button;
void updateChecks();
@@ -24,6 +29,12 @@
virtual int handle( int event );
static void checkChanged( Fl_Widget* w, void* p );
static void applyAllPress( Fl_Widget* w, void* p );
+
+ // constants
+ static const int vm = 2;
+ const int hm;
+ static const int btnH = 25;
+ static const int boxH = 30;
public:
OptionsDlg( int x, int y, int w, int h );
@@ -32,16 +43,11 @@
void show() { Fl_Window::show(); }
void hide() { Fl_Window::hide(); }
- void setOptions( const std::vector<Option>& opts );
+ void setOptions( const std::vector<Option*>& opts );
+ void setOptions( const std::set<Option*, optComp>& opts );
void clearOptions() { options.clear(); }
- const Option changed() const { return changedItem; }
-
- private:
- // constants
- static const int vm = 2;
- const int hm;
- static const int btnH = 25;
- static const int boxH = 30;
+ const event_t event() const { return status; }
+ Option* changed() { return changedItem; }
};
}
Modified: code/stage/trunk/libstage/stage.hh
===================================================================
--- code/stage/trunk/libstage/stage.hh 2008-06-26 20:10:49 UTC (rev 6693)
+++ code/stage/trunk/libstage/stage.hh 2008-06-26 20:29:42 UTC (rev 6694)
@@ -55,6 +55,8 @@
#include <sys/time.h>
#include <iostream>
#include <vector>
+#include <map>
+#include <set>
// we use GLib's data structures extensively. Perhaps we'll move to
// C++ STL types to lose this dependency one day.
@@ -1015,6 +1017,7 @@
//GHashTable* models_by_id; ///< the models that make up the world,
indexed by id
GHashTable* models_by_name; ///< the models that make up the world,
indexed by name
+ std::map< std::string, StgModel* > modelsByName;
GList* velocity_list; ///< a list of models that have non-zero
velocity, for efficient updating
//stg_usec_t wall_last_update; ///< the real time of the last update in ms
@@ -1025,8 +1028,6 @@
int total_subs; ///< the total number of subscriptions to all models
double ppm; ///< the resolution of the world model in pixels per meter
- GList* update_list; //< the descendants that need Update() called
-
void StartUpdatingModel( StgModel* mod );
void StopUpdatingModel( StgModel* mod );
@@ -1055,6 +1056,7 @@
protected:
GHashTable* superregions;
+ GList* update_list; //< the descendants that need Update() called
stg_usec_t interval_sim; ///< temporal resolution: milliseconds that
elapse between simulated time steps
static void UpdateCb( StgWorld* world);
@@ -1168,6 +1170,9 @@
// Draw options
static Option ShowFlags;
+ static Option ShowVisData;
+ static Option ShowBlinken;
+ static Option ShowStatus;
public:
@@ -1359,6 +1364,7 @@
virtual void Draw( uint32_t flags, StgCanvas* canvas );
virtual void DrawBlocks();
+ virtual void DrawStatus( StgCanvas* canvas );
///Draw the image stored in texture_id above the model
void DrawImage( uint32_t texture_id, Stg::StgCanvas* canvas, float
alpha );
@@ -2033,13 +2039,11 @@
/** 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; }
-
-
protected:
virtual void PushColor( stg_color_t col )
@@ -2072,6 +2076,8 @@
// GUI functions
bool saveAsDialog();
bool closeWindowQuery();
+
+ std::set<Option*> DrawOptions;
};
Modified: code/stage/trunk/libstage/world.cc
===================================================================
--- code/stage/trunk/libstage/world.cc 2008-06-26 20:10:49 UTC (rev 6693)
+++ code/stage/trunk/libstage/world.cc 2008-06-26 20:29:42 UTC (rev 6694)
@@ -320,6 +320,7 @@
//g_hash_table_remove_all( models_by_id );
g_hash_table_remove_all( models_by_name );
+ modelsByName.clear();
g_list_free( velocity_list );
velocity_list = NULL;
Modified: code/stage/trunk/libstage/worldgui.cc
===================================================================
--- code/stage/trunk/libstage/worldgui.cc 2008-06-26 20:10:49 UTC (rev
6693)
+++ code/stage/trunk/libstage/worldgui.cc 2008-06-26 20:29:42 UTC (rev
6694)
@@ -97,6 +97,8 @@
#include "stage_internal.hh"
#include "region.hh"
+#include "file_manager.hh"
+#include "options_dlg.hh"
#include <FL/Fl_Image.H>
#include <FL/Fl_Shared_Image.H>
@@ -105,8 +107,7 @@
#include <FL/Fl_Text_Display.H>
#include <FL/Fl_File_Chooser.H>
-#include "file_manager.hh"
-#include "options_dlg.hh"
+#include <set>
static const char* MITEM_VIEW_DATA = "&View/&Data";
@@ -204,54 +205,8 @@
}
-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 );
@@ -416,6 +371,54 @@
return val;
}
+
+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::DrawTree( bool drawall )
{
g_hash_table_foreach( superregions, (GHFunc)SuperRegion::Draw_cb, NULL
);
@@ -429,6 +432,7 @@
}
+
void StgWorldGui::windowCb( Fl_Widget* w, void* p )
{
StgWorldGui* worldGui = static_cast<StgWorldGui*>( p );
@@ -504,8 +508,6 @@
worldGui->saveAsDialog();
}
-
-
void StgWorldGui::fileExitCb( Fl_Widget* w, void* p )
{
StgWorldGui* worldGui = static_cast<StgWorldGui*>( p );
@@ -548,11 +550,19 @@
void StgWorldGui::viewOptionsCb( Fl_Widget* w, void* p ) {
StgWorldGui* worldGui = static_cast<StgWorldGui*>( p );
- std::vector<Option> options;
- for (int i=0; i<10; i++) {
- Option o( i, "Option", i%2*true );
- options.push_back( o );
+// std::set<Option*, bool(*)(const Option*,const Option*)> options(
compare );
+ std::set<Option*, optComp> options;
+ std::vector<Option*> modOpts;
+ for( GList* it=worldGui->update_list; it; it=it->next ) {
+ modOpts = ((StgModel*)it->data)->getOptions();
+ options.insert( modOpts.begin(), modOpts.end() );
}
+
+// std::vector<Option> options;
+// std::set<Option*>::iterator it;
+// for( it=optSet.begin(); it!=optSet.end(); it++ ) {
+// options.push_back( **it );
+// }
if ( !worldGui->oDlg ) {
OptionsDlg* oDlg = new OptionsDlg( 0, 0, 180, 250 );
@@ -586,13 +596,22 @@
Fl::delete_widget( oDlg );
return;
default:
- Option o = oDlg->changed();
- printf( "\"%s\"[%d] changed to %d!\n",
o.name().c_str(), o.id(), o.val() );
- // update flag(s)
+ switch ( oDlg->event() ) {
+ case OptionsDlg::CHANGE:
+ {
+ //Option* o = oDlg->changed();
+ //printf( "\"%s\" changed to %d!\n",
o->name().c_str(), o->val() );
+ break;
+ }
+ case OptionsDlg::CHANGE_ALL:
+ break;
+ case OptionsDlg::NO_EVENT:
+ break;
+ }
+
}
}
-
void aboutOKBtnCb( Fl_Widget* w, void* p ) {
Fl_Return_Button* btn;
btn = static_cast<Fl_Return_Button*>( w );
@@ -664,7 +683,6 @@
win->show();
}
-
bool StgWorldGui::saveAsDialog()
{
const char* newFilename;
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
-------------------------------------------------------------------------
Check out the new SourceForge.net Marketplace.
It's the best place to buy or sell services for
just about anything Open Source.
http://sourceforge.net/services/buy/index.php
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit