Revision: 8287
http://playerstage.svn.sourceforge.net/playerstage/?rev=8287&view=rev
Author: rtv
Date: 2009-10-13 20:10:23 +0000 (Tue, 13 Oct 2009)
Log Message:
-----------
performance tweaks
Modified Paths:
--------------
code/stage/trunk/CMakeLists.txt
code/stage/trunk/RELEASE.txt
code/stage/trunk/examples/ctrl/wander.cc
code/stage/trunk/libstage/block.cc
code/stage/trunk/libstage/blockgroup.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/todo.txt
code/stage/trunk/worlds/fasr.world
code/stage/trunk/worlds/simple.world
Modified: code/stage/trunk/CMakeLists.txt
===================================================================
--- code/stage/trunk/CMakeLists.txt 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/CMakeLists.txt 2009-10-13 20:10:23 UTC (rev 8287)
@@ -2,7 +2,7 @@
SET( V_MAJOR 3 )
SET( V_MINOR 2 )
-SET( V_BUGFIX 0 )
+SET( V_BUGFIX 1 )
SET( VERSION ${V_MAJOR}.${V_MINOR}.${V_BUGFIX} )
SET( APIVERSION ${V_MAJOR}.${V_MINOR} )
Modified: code/stage/trunk/RELEASE.txt
===================================================================
--- code/stage/trunk/RELEASE.txt 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/RELEASE.txt 2009-10-13 20:10:23 UTC (rev 8287)
@@ -1,3 +1,10 @@
+Version 3.2.1
+-------------
+
+Bugfix release, contains mainly bugfixes but some performance tweaks.
+
+Richard Vaughan (rtv) [email protected] - 2009.10.13
+
Version 3.2.0
-------------
Modified: code/stage/trunk/examples/ctrl/wander.cc
===================================================================
--- code/stage/trunk/examples/ctrl/wander.cc 2009-10-13 03:20:17 UTC (rev
8286)
+++ code/stage/trunk/examples/ctrl/wander.cc 2009-10-13 20:10:23 UTC (rev
8287)
@@ -23,11 +23,12 @@
extern "C" int Init( Model* mod, CtrlArgs* args )
{
// local arguments
- printf( "\nWander controller initialised with:\n"
- "\tworldfile string \"%s\"\n"
- "\tcmdline string \"%s\"",
- args->worldfile.c_str(),
- args->cmdline.c_str() );
+ /* printf( "\nWander controller initialised with:\n"
+ "\tworldfile string \"%s\"\n"
+ "\tcmdline string \"%s\"",
+ args->worldfile.c_str(),
+ args->cmdline.c_str() );
+ */
robot_t* robot = new robot_t;
Modified: code/stage/trunk/libstage/block.cc
===================================================================
--- code/stage/trunk/libstage/block.cc 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/libstage/block.cc 2009-10-13 20:10:23 UTC (rev 8287)
@@ -292,14 +292,9 @@
mpts[i] = BlockPointToModelMeters( pts[i] );
}
- // convert the mpts in model coords into global pixel coords
- //gpts.resize(pt_count);
- //for( unsigned int i=0; i<pt_count; i++ )
- //gpts[i] = mod->world->MetersToPixels( mod->LocalToGlobal( mpts[i] ));
-
gpts.clear();
mod->LocalToPixels( mpts, gpts );
-
+
for( unsigned int i=0; i<pt_count; i++ )
mod->world->ForEachCellInLine( gpts[i],
gpts[(i+1)%pt_count],
Modified: code/stage/trunk/libstage/blockgroup.cc
===================================================================
--- code/stage/trunk/libstage/blockgroup.cc 2009-10-13 03:20:17 UTC (rev
8286)
+++ code/stage/trunk/libstage/blockgroup.cc 2009-10-13 20:10:23 UTC (rev
8287)
@@ -238,7 +238,7 @@
void BlockGroup::CallDisplayList( Model* mod )
{
if( displaylist == 0 )
- BuildDisplayList( mod );
+ BuildDisplayList( mod );
glCallList( displaylist );
}
Modified: code/stage/trunk/libstage/model.cc
===================================================================
--- code/stage/trunk/libstage/model.cc 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/libstage/model.cc 2009-10-13 20:10:23 UTC (rev 8287)
@@ -149,6 +149,8 @@
// static members
uint32_t Model::count = 0;
+uint32_t Model::trail_length = 50;
+uint64_t Model::trail_interval = 5;
std::map<stg_id_t,Model*> Model::modelsbyid;
std::map<std::string, creator_t> Model::name_map;
std::map<void*, std::set<Model::stg_cb_t> > Model::callbacks;
@@ -288,8 +290,6 @@
subs(0),
thread_safe( false ),
trail(),
- trail_length(50),
- trail_interval(5),
type(type),
event_queue_num( 0 ),
used(false),
@@ -582,12 +582,16 @@
void Model::LocalToPixels( const std::vector<stg_point_t>& local,
std::vector<stg_point_int_t>& global) const
{
+ Pose gpose = GetGlobalPose() + geom.pose;
+
FOR_EACH( it, local )
- global.push_back( world->MetersToPixels( LocalToGlobal( *it )));
+ {
+ Pose ptpose = gpose + Pose( it->x, it->y, 0, 0 );
+ global.push_back( stg_point_int_t( (int32_t)floor(
ptpose.x * world->ppm) ,
+
(int32_t)floor( ptpose.y * world->ppm) ));
+ }
}
-
-
void Model::MapWithChildren()
{
UnMap();
@@ -898,16 +902,16 @@
// ConditionalMove() returns a pointer to the model we hit, or
// NULL. We use this as a boolean for SetStall()
SetStall( ConditionalMove( pose + p ) );
-
- if( trail_length > 0 && world->updates % trail_interval == 0 )
- {
- trail.push_back( TrailItem( world->sim_time, GetGlobalPose(),
color ) );
-
- if( trail.size() > trail_length )
- trail.pop_front();
- }
}
+void Model::UpdateTrail()
+{
+ trail.push_back( TrailItem( world->sim_time, GetGlobalPose(), color )
);
+
+ if( trail.size() > trail_length )
+ trail.pop_front();
+}
+
Model* Model::GetUnsubscribedModelOfType( const std::string& type ) const
{
if( (this->type == type) && (this->subs == 0) )
Modified: code/stage/trunk/libstage/model_laser.cc
===================================================================
--- code/stage/trunk/libstage/model_laser.cc 2009-10-13 03:20:17 UTC (rev
8286)
+++ code/stage/trunk/libstage/model_laser.cc 2009-10-13 20:10:23 UTC (rev
8287)
@@ -73,9 +73,9 @@
ModelLaser::ModelLaser( World* world,
- Model* parent,
- const
std::string& type ) :
- Model( world, parent, type ),
+
Model* parent,
+
const std::string& type ) :
+ Model( world, parent, type ),
vis( world ),
sample_count( DEFAULT_SAMPLES ),
samples(),
@@ -84,7 +84,7 @@
resolution( DEFAULT_RESOLUTION )
{
PRINT_DEBUG2( "Constructing ModelLaser %d (%s)\n",
- id, typestr );
+ id, typestr );
SetGeom( Geom( Pose(0,0,0,0), DEFAULT_SIZE) );
@@ -148,8 +148,8 @@
}
static bool laser_raytrace_match( Model* hit,
- Model* finder,
- const void*
dummy )
+
Model* finder,
+
const void* dummy )
{
// Ignore the model that's looking and things that are invisible to
// lasers
@@ -184,39 +184,39 @@
// trace the ray, incrementing its heading for each sample
for( unsigned int t(0); t<sample_count; t += resolution )
{
- stg_raytrace_result_t r( world->Raytrace( ray ) );
- samples[t].range = r.range;
+ stg_raytrace_result_t r( world->Raytrace( ray ) );
+ samples[t].range = r.range;
// if we hit a model and it reflects brightly, we set
// reflectance high, else low
if( r.mod && ( r.mod->vis.laser_return >= LaserBright ) )
- samples[t].reflectance = 1;
+ samples[t].reflectance = 1;
else
- samples[t].reflectance = 0;
+ samples[t].reflectance = 0;
- // point the ray to the next angle
- ray.origin.a += sample_incr;
+ // point the ray to the next angle
+ ray.origin.a += sample_incr;
}
// we may need to interpolate the samples we skipped
if( resolution > 1 )
{
for( unsigned int t( resolution); t<sample_count; t+=resolution )
- for( unsigned int g(1); g<resolution; g++ )
- {
- if( t >= sample_count )
- break;
+ for( unsigned int g(1); g<resolution; g++ )
+ {
+ if( t >= sample_count )
+ break;
- // copy the rightmost sample data into this point
- samples[t-g] = samples[t-resolution];
+ // copy the rightmost sample
data into this point
+ samples[t-g] =
samples[t-resolution];
- double left( samples[t].range );
- double right( samples[t-resolution].range );
+ double left( samples[t].range );
+ double right(
samples[t-resolution].range );
- // linear range interpolation between the left and
right samples
- samples[t-g].range = (left-g*(left-right)/resolution);
- }
- }
+ // linear range interpolation
between the left and right samples
+ samples[t-g].range =
(left-g*(left-right)/resolution);
+ }
+ }
// removed MapFromRoot() optimization - though neat, it breaks
// thread-safety by messing with the Cell contents - rtv
@@ -243,12 +243,12 @@
printf( "\tRanges[ " );
for( unsigned int i=0; i<sample_count; i++ )
- printf( "%.2f ", samples[i].range );
+ printf( "%.2f ", samples[i].range );
puts( " ]" );
printf( "\tReflectance[ " );
for( unsigned int i=0; i<sample_count; i++ )
- printf( "%.2f ", samples[i].reflectance );
+ printf( "%.2f ", samples[i].reflectance );
puts( " ]" );
}
@@ -302,74 +302,74 @@
glPointSize( 2 );
for( unsigned int s(0); s<sample_count; s++ )
- {
- double ray_angle = (s * (laser->fov / (sample_count-1))) -
laser->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) );
+ {
+ double ray_angle = (s * (laser->fov /
(sample_count-1))) - laser->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();
- }
- }
+ // 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();
+ }
+ }
glVertexPointer( 2, GL_FLOAT, 0, &pts[0] );
laser->PopColor();
if( showArea )
- {
- // draw the filled polygon in transparent blue
- laser->PushColor( 0, 0, 1, 0.1 );
- glDrawArrays( GL_POLYGON, 0, sample_count+1 );
- laser->PopColor();
- }
+ {
+ // draw the filled polygon in transparent blue
+ laser->PushColor( 0, 0, 1, 0.1 );
+ glDrawArrays( GL_POLYGON, 0, sample_count+1 );
+ laser->PopColor();
+ }
glDepthMask( GL_TRUE );
if( showStrikes )
- {
- // draw the beam strike points
- laser->PushColor( 0, 0, 1, 0.8 );
- glDrawArrays( GL_POINTS, 0, sample_count+1 );
- laser->PopColor();
- }
+ {
+ // draw the beam strike points
+ laser->PushColor( 0, 0, 1, 0.8 );
+ glDrawArrays( GL_POINTS, 0, sample_count+1 );
+ laser->PopColor();
+ }
if( showFov )
- {
- for( unsigned int s(0); s<sample_count; s++ )
{
- double ray_angle((s * (laser->fov / (sample_count-1))) -
laser->fov/2.0);
- pts[2*s+2] = (float)(laser->range_max * cos(ray_angle) );
- pts[2*s+3] = (float)(laser->range_max * sin(ray_angle) );
- }
+ for( unsigned int s(0); s<sample_count; s++ )
+ {
+ double ray_angle((s * (laser->fov /
(sample_count-1))) - laser->fov/2.0);
+ pts[2*s+2] = (float)(laser->range_max *
cos(ray_angle) );
+ pts[2*s+3] = (float)(laser->range_max *
sin(ray_angle) );
+ }
- glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
- laser->PushColor( 0, 0, 1, 0.5 );
- glDrawArrays( GL_POLYGON, 0, sample_count+1 );
- laser->PopColor();
- }
+ glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
+ laser->PushColor( 0, 0, 1, 0.5 );
+ glDrawArrays( GL_POLYGON, 0, sample_count+1 );
+ laser->PopColor();
+ }
if( showBeams )
- {
- laser->PushColor( 0, 0, 1, 0.5 );
- glBegin( GL_LINES );
+ {
+ laser->PushColor( 0, 0, 1, 0.5 );
+ glBegin( GL_LINES );
- for( unsigned int s(0); s<sample_count; s++ )
- {
+ for( unsigned int s(0); s<sample_count; s++ )
+ {
- glVertex2f( 0,0 );
- double ray_angle((s * (laser->fov / (sample_count-1))) -
laser->fov/2.0);
- glVertex2f( samples[s].range * cos(ray_angle),
- samples[s].range * sin(ray_angle) );
+ glVertex2f( 0,0 );
+ double ray_angle((s * (laser->fov /
(sample_count-1))) - laser->fov/2.0);
+ glVertex2f( samples[s].range *
cos(ray_angle),
+
samples[s].range * sin(ray_angle) );
- }
- glEnd();
- laser->PopColor();
- }
+ }
+ glEnd();
+ laser->PopColor();
+ }
glPopMatrix();
}
Modified: code/stage/trunk/libstage/stage.hh
===================================================================
--- code/stage/trunk/libstage/stage.hh 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/libstage/stage.hh 2009-10-13 20:10:23 UTC (rev 8287)
@@ -1825,11 +1825,14 @@
/** The maxiumum length of the trail drawn. Default is 20, but can
be set in the world file using the tail_length model
property. */
- unsigned int trail_length;
+ static unsigned int trail_length;
/** Number of world updates between trail records. */
- uint64_t trail_interval;
+ static uint64_t trail_interval;
+ /** Record the current pose in our trail. Delete the trail head
if it is full. */
+ void UpdateTrail();
+
//stg_model_type_t type;
const std::string type;
/** The index into the world's vector of event queues. Initially
Modified: code/stage/trunk/libstage/world.cc
===================================================================
--- code/stage/trunk/libstage/world.cc 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/libstage/world.cc 2009-10-13 20:10:23 UTC (rev 8287)
@@ -556,7 +556,11 @@
FOR_EACH( it, active_energy )
(*it)->UpdateCharge();
-
+
+ if( Model::trail_length > 0 && updates % Model::trail_interval == 0 )
+ FOR_EACH( it, active_velocity )
+ (*it)->UpdateTrail();
+
if( show_clock && ((this->updates % show_clock_interval) == 0) )
{
printf( "\r[Stage: %s]", ClockString().c_str() );
Modified: code/stage/trunk/todo.txt
===================================================================
--- code/stage/trunk/todo.txt 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/todo.txt 2009-10-13 20:10:23 UTC (rev 8287)
@@ -16,8 +16,8 @@
19.94 (rev 8210 - new event queue is slower but more powerful and
elegant)
MBA 17.3
+MBA 23.2
-
** 3.2.0 RELEASE *
- visualizer option state in worldfile
Modified: code/stage/trunk/worlds/fasr.world
===================================================================
--- code/stage/trunk/worlds/fasr.world 2009-10-13 03:20:17 UTC (rev 8286)
+++ code/stage/trunk/worlds/fasr.world 2009-10-13 20:10:23 UTC (rev 8287)
@@ -10,8 +10,8 @@
paused 1
# time at which to pause (in GUI mode) or quit (in headless mode) the
simulation
-#quit_time 3600 # 1 hour of simulated time
-quit_time 1800 # hour of simulated time
+quit_time 3600 # 1 hour of simulated time
+#quit_time 1800 # hour of simulated time
resolution 0.02
@@ -102,6 +102,9 @@
joules_capacity 400000
fiducial_return 0
charging_bump( fiducial( range_max 5 pose [ 0 0 -0.100 0 ] ) )
+
+ # small speed optimization
+ trail_length 0
)
autorob( pose [7.062 -1.563 0 152.684] joules 300000 name "r0" )
Modified: code/stage/trunk/worlds/simple.world
===================================================================
--- code/stage/trunk/worlds/simple.world 2009-10-13 03:20:17 UTC (rev
8286)
+++ code/stage/trunk/worlds/simple.world 2009-10-13 20:10:23 UTC (rev
8287)
@@ -17,8 +17,7 @@
window
(
size [ 635.000 666.000 ] # in pixels
- scale 37.481
- # pixels per meteri
+ scale 37.481 # pixels per meter
center [ -0.019 -0.282 ]
rotate [ 0 0 ]
@@ -29,11 +28,9 @@
floorplan
(
name "cave"
- #size [16.000 16.000 0.800]
- size [ 66 66 0.800]
+ size [16.000 16.000 0.800]
pose [0 0 0 0]
- #bitmap "bitmaps/cave.png"
- bitmap "bitmaps/circle.png"
+ bitmap "bitmaps/cave.png"
)
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
Come build with us! The BlackBerry(R) Developer Conference in SF, CA
is the only developer event you need to attend this year. Jumpstart your
developing skills, take BlackBerry mobile applications to market and stay
ahead of the curve. Join us from November 9 - 12, 2009. Register now!
http://p.sf.net/sfu/devconference
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit