Revision: 7555
http://playerstage.svn.sourceforge.net/playerstage/?rev=7555&view=rev
Author: rtv
Date: 2009-03-28 21:26:54 +0000 (Sat, 28 Mar 2009)
Log Message:
-----------
cleaning up, using references for common method args and improving
const-correctness
Modified Paths:
--------------
code/stage/trunk/examples/ctrl/fasr.cc
code/stage/trunk/examples/ctrl/sink.cc
code/stage/trunk/examples/ctrl/source.cc
code/stage/trunk/examples/ctrl/wander.cc
code/stage/trunk/libstage/blockgroup.cc
code/stage/trunk/libstage/model.cc
code/stage/trunk/libstage/model_getset.cc
code/stage/trunk/libstage/model_position.cc
code/stage/trunk/libstage/model_props.cc
code/stage/trunk/libstage/powerpack.cc
code/stage/trunk/libstage/stage.cc
code/stage/trunk/libstage/stage.hh
Modified: code/stage/trunk/examples/ctrl/fasr.cc
===================================================================
--- code/stage/trunk/examples/ctrl/fasr.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/examples/ctrl/fasr.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -390,23 +390,18 @@
//pose.z += 0.0001;
//robot->pos->SetPose( pose );
-
+
if( pos->GetFlagCount() < payload &&
hypot( -7-pose.x, -7-pose.y ) < 2.0 )
{
if( ++robot->work_get > workduration )
{
- // protect source from concurrent access
- robot->source->Lock();
-
// transfer a chunk from source to robot
pos->PushFlag( robot->source->PopFlag() );
- robot->source->Unlock();
-
robot->work_get = 0;
- }
+ }
}
-
+
robot->at_dest = false;
if( hypot( 7-pose.x, 7-pose.y ) < 1.0 )
@@ -417,16 +412,10 @@
if( ++robot->work_put > workduration )
{
- // protect sink from concurrent access
- robot->sink->Lock();
-
//puts( "dropping" );
// transfer a chunk between robot and goal
robot->sink->PushFlag( pos->PopFlag() );
- robot->sink->Unlock();
-
robot->work_put = 0;
-
}
}
Modified: code/stage/trunk/examples/ctrl/sink.cc
===================================================================
--- code/stage/trunk/examples/ctrl/sink.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/examples/ctrl/sink.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -7,11 +7,10 @@
// Stage calls this when the model starts up
extern "C" int Init( Model* mod )
-{
+{
+ //for( int i=0; i<5; i++ )
+ // mod->PushFlag( new Flag( stg_color_pack( 1,1,0,0), 0.5 ) );
- for( int i=0; i<5; i++ )
- mod->PushFlag( new Flag( stg_color_pack( 1,1,0,0), 0.5 ) );
-
mod->AddUpdateCallback( (stg_model_callback_t)Update, NULL );
return 0; //ok
@@ -20,14 +19,8 @@
// inspect the laser data and decide what to do
int Update( Model* mod, void* dummy )
{
- // protect access to this model from other controllers
- mod->Lock();
-
if( mod->GetWorld()->GetUpdateCount() % INTERVAL == 0 )
mod->PopFlag();
-
- mod->Unlock();
-
return 0; // run again
}
Modified: code/stage/trunk/examples/ctrl/source.cc
===================================================================
--- code/stage/trunk/examples/ctrl/source.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/examples/ctrl/source.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -21,14 +21,9 @@
// inspect the laser data and decide what to do
int Update( Model* mod, void* dummy )
{
- // protect access to this model from other controllers
- mod->Lock();
-
if( mod->GetWorld()->GetUpdateCount() % INTERVAL == 0 )
mod->PushFlag( new Flag( stg_color_pack( 1,1,0,0), flagsz ) );
- mod->Unlock();
-
return 0; // run again
}
Modified: code/stage/trunk/examples/ctrl/wander.cc
===================================================================
--- code/stage/trunk/examples/ctrl/wander.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/examples/ctrl/wander.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -120,7 +120,13 @@
robot->pos->SetXSpeed( cruisespeed );
robot->pos->SetTurnSpeed( 0 );
}
-
+
+ if( robot->pos->Stalled() )
+ {
+ robot->pos->SetSpeed( 0,0,0 );
+ robot->pos->SetTurnSpeed( 0 );
+ }
+
return 0;
}
Modified: code/stage/trunk/libstage/blockgroup.cc
===================================================================
--- code/stage/trunk/libstage/blockgroup.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/libstage/blockgroup.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -58,17 +58,12 @@
Model* BlockGroup::TestCollision()
{
- //printf( "blockgroup %p test collision...\n", this );
-
Model* hitmod = NULL;
for( GList* it=blocks; it; it = it->next )
if( (hitmod = ((Block*)it->data)->TestCollision()))
break; // bail on the earliest collision
-
- //printf( "blockgroup %p test collision done.\n", this );
-
- return hitmod;
+ return hitmod; // NULL if no collision
}
@@ -107,10 +102,6 @@
offset.x = minx + size.x/2.0;
offset.y = miny + size.y/2.0;
offset.z = 0; // todo?
-
- // normalize blocks
- // for( GList* it = blocks; itl it=it->next )
- //((Block*)it->data)->Normalize( size.x, size.y, size.z, offset.x
}
@@ -282,11 +273,6 @@
if( rects && (rect_count > 0) )
{
- // shift the origin from bottom-left to center of the image
- //double dx = width/2.0;
- //double dy = height/2.0;
-
- //puts( "loading rects" );
for( unsigned int r=0; r<rect_count; r++ )
{
stg_point_t pts[4];
@@ -296,15 +282,6 @@
double w = rects[r].size.x;
double h = rects[r].size.y;
-// pts[0].x = x - dx;
-// pts[0].y = y - dy;
-// pts[1].x = x + w - dx;
-// pts[1].y = y -dy;
-// pts[2].x = x + w -dx;
-// pts[2].y = y + h -dy;
-// pts[3].x = x - dx;
-// pts[3].y = y + h -dy;
-
pts[0].x = x;
pts[0].y = y;
pts[1].x = x + w;
@@ -318,10 +295,10 @@
stg_color_t col = stg_color_pack( 1.0, 0,0,1.0 );
AppendBlock( new Block( mod,
-
pts,4,
-
0,1,
-
col,
-
true ) );
+
pts,4,
+
0,1,
+
col,
+
true ) );
}
free( rects );
}
Modified: code/stage/trunk/libstage/model.cc
===================================================================
--- code/stage/trunk/libstage/model.cc 2009-03-28 00:10:37 UTC (rev 7554)
+++ code/stage/trunk/libstage/model.cc 2009-03-28 21:26:54 UTC (rev 7555)
@@ -472,7 +472,7 @@
}
// convert a global pose into the model's local coordinate system
-Pose Model::GlobalToLocal( Pose pose )
+Pose Model::GlobalToLocal( const Pose& pose ) const
{
// get model's global pose
Pose org = GetGlobalPose();
@@ -500,7 +500,7 @@
}
// returns true iff model [testmod] is an antecedent of this model
-bool Model::IsAntecedent( Model* testmod )
+bool Model::IsAntecedent( const Model* testmod ) const
{
if( parent == NULL )
return false;
@@ -512,7 +512,7 @@
}
// returns true iff model [testmod] is a descendent of this model
-bool Model::IsDescendent( Model* testmod )
+bool Model::IsDescendent( const Model* testmod ) const
{
if( this == testmod )
return true;
@@ -528,14 +528,14 @@
return false;
}
-bool Model::IsRelated( Model* that )
+bool Model::IsRelated( const Model* that ) const
{
// is it me?
if( this == that )
return true;
// wind up to top-level object
- Model* candidate = this;
+ Model* candidate = (Model*)this;
while( candidate->parent )
candidate = candidate->parent;
@@ -543,9 +543,7 @@
return candidate->IsDescendent( that );
}
-
-
-inline Pose Model::LocalToGlobal( Pose pose )
+inline Pose Model::LocalToGlobal( const Pose& pose ) const
{
return pose_sum( pose_sum( GetGlobalPose(), geom.pose ), pose );
}
@@ -612,7 +610,7 @@
pose->a = pose->a;
}
-void Model::Print( char* prefix )
+void Model::Print( char* prefix ) const
{
if( prefix )
printf( "%s model ", prefix );
@@ -628,7 +626,7 @@
((Model*)it->data)->Print( prefix );
}
-const char* Model::PrintWithPose()
+const char* Model::PrintWithPose() const
{
Pose gpose = GetGlobalPose();
@@ -678,6 +676,10 @@
void Model::Update( void )
{
+ // NOTE - update callbacks are NOT called from here, as this method
+ // may be called in multiple threads, and callbacks may not be
+ // reentrant
+
// printf( "[%llu] %s update (%d subs)\n",
// this->world->sim_time, this->token, this->subs );
@@ -688,22 +690,8 @@
{
// consume energy stored in the power pack
stg_joules_t consumed = watts * (world->interval_sim * 1e-6);
- pp->Subtract( consumed );
-
- /*
- printf ( "%s current %.2f consumed %.6f ppack @ %p [ %.2f/%.2f
(%.0f)\n",
- token,
- watts,
- consumed,
- power_pack,
- power_pack->stored,
- power_pack->capacity,
- power_pack->stored / power_pack->capacity * 100.0 );
- */
+ pp->Subtract( consumed );
}
-
- //CallCallbacks( &hooks.update );
- //last_update = world->sim_time;
}
void Model::CallUpdateCallbacks( void )
@@ -712,7 +700,7 @@
last_update = world->sim_time;
}
-stg_meters_t Model::ModelHeight()
+stg_meters_t Model::ModelHeight() const
{
stg_meters_t m_child = 0; //max size of any child
for( GList* it=this->children; it; it=it->next )
@@ -729,25 +717,20 @@
void Model::AddToPose( double dx, double dy, double dz, double da )
{
- if( dx || dy || dz || da )
- {
- Pose pose = GetPose();
- pose.x += dx;
- pose.y += dy;
- pose.z += dz;
- pose.a += da;
-
- SetPose( pose );
- }
+ Pose pose = this->GetPose();
+ pose.x += dx;
+ pose.y += dy;
+ pose.z += dz;
+ pose.a += da;
+
+ this->SetPose( pose );
}
-void Model::AddToPose( Pose pose )
+void Model::AddToPose( const Pose& pose )
{
this->AddToPose( pose.x, pose.y, pose.z, pose.a );
}
-
-
void Model::PlaceInFreeSpace( stg_meters_t xmin, stg_meters_t xmax,
stg_meters_t ymin, stg_meters_t ymax )
{
@@ -836,10 +819,6 @@
Model* Model::ConditionalMove( Pose newpose )
{
-// if( isnan( pose.x ) || isnan( pose.y ) || isnan( pose.z ) || isnan(
pose.a ) )
-// printf( "ConditionalMove bad newpose %s [%.2f %.2f %.2f %.2f]\n",
-// token, newpose.x, newpose.y, newpose.z, newpose.a );
-
Pose startpose = pose;
pose = newpose; // do the move provisionally - we might undo it below
@@ -853,10 +832,6 @@
world->dirty = true; // need redraw
}
-// if( isnan( pose.x ) || isnan( pose.y ) || isnan( pose.z ) || isnan(
pose.a ) )
-// printf( "ConditionalMove bad pose %s [%.2f %.2f %.2f %.2f]\n",
-// token, pose.x, pose.y, pose.z, pose.a );
-
return hitmod;
}
@@ -866,12 +841,6 @@
if( disabled )
return;
-// if( velocity.IsZero() )
-// {
-// PRINT_WARN1( "model %s has velocity zero but its pose is being
updated", token );
-// return;
-// }
-
// TODO - control this properly, and maybe do it faster
//if( 0 )
//if( (world->updates % 10 == 0) )
@@ -897,9 +866,9 @@
p.z = velocity.z * interval;
p.a = velocity.a * interval;
- if( isnan( p.x ) || isnan( p.y ) || isnan( p.z ) || isnan( p.a ) )
- printf( "UpdatePose bad vel %s [%.2f %.2f %.2f %.2f]\n",
- token, p.x, p.y, p.z, p.a );
+ //if( isnan( p.x ) || isnan( p.y ) || isnan( p.z ) || isnan( p.a ) )
+ //printf( "UpdatePose bad vel %s [%.2f %.2f %.2f %.2f]\n",
+ // token, p.x, p.y, p.z, p.a );
// attempts to move to the new pose. If the move fails because we'd
// hit another model, that model is returned.
@@ -909,9 +878,9 @@
}
-int Model::TreeToPtrArray( GPtrArray* array )
+int Model::TreeToPtrArray( GPtrArray* array ) const
{
- g_ptr_array_add( array, this );
+ g_ptr_array_add( array, (void*)this );
//printf( " added %s to array at %p\n", root->token, array );
@@ -923,10 +892,10 @@
return added;
}
-Model* Model::GetUnsubscribedModelOfType( stg_model_type_t type )
+Model* Model::GetUnsubscribedModelOfType( stg_model_type_t type ) const
{
if( (this->type == type) && (this->subs == 0) )
- return this;
+ return (Model*)this; // discard const
// this model is no use. try children recursively
for( GList* it = children; it; it=it->next )
@@ -959,7 +928,7 @@
if( (this->type == type) && (!this->used ) )
{
this->used = true;
- return this;
+ return this; // discard const
}
// this model is no use. try children recursively
@@ -977,7 +946,7 @@
}
-Model* Model::GetModel( const char* modelname )
+Model* Model::GetModel( const char* modelname ) const
{
// construct the full model name and look it up
char* buf = new char[TOKEN_MAX];
@@ -1012,7 +981,7 @@
world->dirty = true;
}
-PowerPack* Model::FindPowerPack()
+PowerPack* Model::FindPowerPack() const
{
if( power_pack )
return power_pack;
Modified: code/stage/trunk/libstage/model_getset.cc
===================================================================
--- code/stage/trunk/libstage/model_getset.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/libstage/model_getset.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -2,11 +2,11 @@
using namespace Stg;
-void Model::SetGeom( Geom geom )
+void Model::SetGeom( const Geom& g )
{
UnMapWithChildren();
- this->geom = geom;
+ this->geom = g;
blockgroup.CalcSize();
@@ -121,12 +121,12 @@
}
// set the pose of model in global coordinates
-void Model::SetGlobalPose( Pose gpose )
+void Model::SetGlobalPose( const Pose& gpose )
{
SetPose( parent ? parent->GlobalToLocal( gpose ) : gpose );
}
-int Model::SetParent( Model* newparent)
+int Model::SetParent( Model* newparent)
{
// remove the model from its old parent (if it has one)
if( this->parent )
@@ -143,7 +143,7 @@
}
// get the model's velocity in the global frame
-Velocity Model::GetGlobalVelocity()
+Velocity Model::GetGlobalVelocity() const
{
Pose gpose = GetGlobalPose();
@@ -159,7 +159,7 @@
}
// set the model's velocity in the global frame
-void Model::SetGlobalVelocity( Velocity gv )
+void Model::SetGlobalVelocity( const Velocity& gv )
{
Pose gpose = GetGlobalPose();
@@ -175,7 +175,7 @@
}
// get the model's position in the global frame
-Pose Model::GetGlobalPose()
+Pose Model::GetGlobalPose() const
{
// if I'm a top level model, my global pose is my local pose
if( parent == NULL )
@@ -191,7 +191,7 @@
}
-void Model::SetVelocity( Velocity vel )
+void Model::SetVelocity( const Velocity& vel )
{
// assert( ! isnan(vel.x) );
// assert( ! isnan(vel.y) );
@@ -217,7 +217,7 @@
// set the model's pose in the local frame
-void Model::SetPose( Pose newpose )
+void Model::SetPose( const Pose& newpose )
{
// if the pose has changed, we need to do some work
if( memcmp( &pose, &newpose, sizeof(Pose) ) != 0 )
Modified: code/stage/trunk/libstage/model_position.cc
===================================================================
--- code/stage/trunk/libstage/model_position.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/libstage/model_position.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -104,10 +104,9 @@
// no power consumed until we're subscribed
this->SetWatts( 0 );
- // sensible position defaults
- Velocity vel;
- memset( &vel, 0, sizeof(vel));
- this->SetVelocity( vel );
+ // zero vel
+ Velocity v; // initially zero
+ this->SetVelocity( v );
this->SetBlobReturn( TRUE );
@@ -655,7 +654,7 @@
Gl::pose_inverse_shift( pose );
Gl::pose_shift( est_origin );
- glTranslatef( 0,0, 0.02 );
+ glTranslatef( 0,0,0.02 );
// draw waypoints
for( unsigned int i=0; i < waypoint_count; i++ )
Modified: code/stage/trunk/libstage/model_props.cc
===================================================================
--- code/stage/trunk/libstage/model_props.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/libstage/model_props.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -4,7 +4,7 @@
#define MATCH(A,B) (strcmp(A,B)== 0)
-void* Model::GetProperty( const char* key )
+void* Model::GetProperty( const char* key ) const
{
// see if the key has the predefined-property prefix
if( strncmp( key, MP_PREFIX, strlen(MP_PREFIX)) == 0 )
@@ -23,7 +23,7 @@
}
// otherwise it may be an arbitrary named property
- return g_datalist_get_data( &this->props, key );
+ return g_datalist_get_data( (GData**)&this->props, key ); // cast to
discard const
}
int Model::SetProperty( const char* key,
@@ -94,7 +94,7 @@
}
-bool Model::GetPropertyFloat( const char* key, float* f, float defaultval )
+bool Model::GetPropertyFloat( const char* key, float* f, float defaultval )
const
{
float* fp = (float*)GetProperty( key );
if( fp )
@@ -107,7 +107,7 @@
return false;
}
-bool Model::GetPropertyInt( const char* key, int* i, int defaultval )
+bool Model::GetPropertyInt( const char* key, int* i, int defaultval ) const
{
int* ip = (int*)GetProperty( key );
if( ip )
@@ -120,7 +120,7 @@
return false;
}
-bool Model::GetPropertyStr( const char* key, char** c, char* defaultval )
+bool Model::GetPropertyStr( const char* key, char** c, char* defaultval ) const
{
char* cp = (char*)GetProperty( key );
Modified: code/stage/trunk/libstage/powerpack.cc
===================================================================
--- code/stage/trunk/libstage/powerpack.cc 2009-03-28 00:10:37 UTC (rev
7554)
+++ code/stage/trunk/libstage/powerpack.cc 2009-03-28 21:26:54 UTC (rev
7555)
@@ -34,25 +34,6 @@
const double height = 0.5;
const double width = 0.2;
- // draw an electric zap
-// glPolygonMode( GL_FRONT, GL_LINE );
-// glBegin( GL_POLYGON );
-// glVertex2i( 0, 0 );
-// glVertex2i( 3, 2 );
-// glVertex2i( 1, 2 );
-// glEnd();
-
-// glVertex2i( 1, 3 );
-// glVertex2i( 0, 3 );
-// glVertex2i( 1, 5 );
-// glVertex2i( 3, 5 );
-// glVertex2i( 4, 3 );
-// glVertex2i( 5, 3 );
-// glVertex2i( 4, 4 );
-// glVertex2i( 5, 4);
-// glEnd();
- //}
-
double percent = stored/capacity * 100.0;
const double alpha = 0.5;
@@ -130,7 +111,7 @@
//gl_draw_string( -0.2, 0, 0, buf );
// ?
- glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
+ // glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
}
@@ -163,7 +144,6 @@
// we can't transfer more than he can take
amount = MIN( amount, dest->RemainingCapacity() );
-
//printf( "%s gives %.3f J to %s\n",
// mod->Token(), amount, dest->mod->Token() );
Modified: code/stage/trunk/libstage/stage.cc
===================================================================
--- code/stage/trunk/libstage/stage.cc 2009-03-28 00:10:37 UTC (rev 7554)
+++ code/stage/trunk/libstage/stage.cc 2009-03-28 21:26:54 UTC (rev 7555)
@@ -72,10 +72,10 @@
-void Stg::stg_print_velocity( Velocity* vel )
+void Stg::stg_print_velocity( const Velocity& vel )
{
printf( "velocity [x:%.3f y:%.3f a:%.3f]\n",
- vel->x, vel->y, vel->a );
+ vel.x, vel.y, vel.a );
}
Modified: code/stage/trunk/libstage/stage.hh
===================================================================
--- code/stage/trunk/libstage/stage.hh 2009-03-28 00:10:37 UTC (rev 7554)
+++ code/stage/trunk/libstage/stage.hh 2009-03-28 21:26:54 UTC (rev 7555)
@@ -153,10 +153,10 @@
/** convert an angle in radians to degrees. */
inline double rtod( double r ){ return( r*180.0/M_PI ); }
-
+
/** convert an angle in degrees to radians. */
inline double dtor( double d ){ return( d*M_PI/180.0 ); }
-
+
/** Normalize an angle to within +/_ M_PI. */
inline double normalize( const double a )
{
@@ -280,7 +280,8 @@
prefix, x,y,z,a );
}
- bool IsZero(){ return( !(x || y || z || a )); };
+ /* returns true iff all components of the velocity are zero. */
+ bool IsZero() const { return( !(x || y || z || a )); };
void Load( Worldfile* wf, int section, const char* keyword );
void Save( Worldfile* wf, int section, const char* keyword );
@@ -565,7 +566,7 @@
database, a bright red color (0xF00) will be returned instead.
*/
stg_color_t stg_lookup_color(const char *name);
-
+
/** returns the sum of [p1] + [p2], in [p1]'s coordinate system */
inline Pose pose_sum( const Pose& p1, const Pose& p2 )
{
@@ -590,11 +591,11 @@
/** Report an error, with a standard, friendly message header */
void stg_print_err( const char* err );
/** Print human-readable geometry on stdout */
- void stg_print_geom( Geom* geom );
+ void stg_print_geom( const Geom& geom );
/** Print human-readable pose on stdout */
- void stg_print_pose( Pose* pose );
+ void stg_print_pose( const Pose& pose );
/** Print human-readable velocity on stdout */
- void stg_print_velocity( Velocity* vel );
+ void stg_print_velocity( const Velocity& vel );
/** A model creator function. Each model type must define a function of this
type. */
typedef Model* (*stg_creator_t)( World*, Model* );
@@ -975,7 +976,7 @@
Worldfile* GetWorldFile(){ return wf; };
- inline virtual bool IsGUI() { return false; }
+ virtual bool IsGUI() { return false; }
virtual void Load( const char* worldfile_path );
virtual void UnLoad();
@@ -989,7 +990,7 @@
void CancelQuit(){ quit = false; }
void CancelQuitAll(){ quit_all = false; }
- void TryCharge( PowerPack* pp, Pose pose );
+ void TryCharge( PowerPack* pp, const Pose& pose );
/** Get the resolution in pixels-per-metre of the underlying
discrete raytracing model */
@@ -1201,13 +1202,13 @@
virtual void Draw( void ) const = 0;
virtual void SetProjection( void ) const = 0;
- inline float yaw( void ) const { return _yaw; }
- inline float pitch( void ) const { return _pitch; }
-
- inline float x( void ) const { return _x; }
- inline float y( void ) const { return _y; }
- inline float z( void ) const { return _z; }
-
+ float yaw( void ) const { return _yaw; }
+ float pitch( void ) const { return _pitch; }
+
+ float x( void ) const { return _x; }
+ float y( void ) const { return _y; }
+ float z( void ) const { return _z; }
+
virtual void reset() = 0;
virtual void Load( Worldfile* wf, int sec ) = 0;
@@ -1235,34 +1236,34 @@
void strafe( float amount );
void forward( float amount );
- inline void setPose( float x, float y, float z ) { _x = x; _y = y; _z = z;
}
- inline void addPose( float x, float y, float z ) { _x += x; _y += y; _z +=
z; if( _z < 0.1 ) _z = 0.1; }
+ void setPose( float x, float y, float z ) { _x = x; _y = y; _z = z; }
+ void addPose( float x, float y, float z ) { _x += x; _y += y; _z += z;
if( _z < 0.1 ) _z = 0.1; }
void move( float x, float y, float z );
- inline void setFov( float horiz_fov, float vert_fov ) { _horiz_fov =
horiz_fov; _vert_fov = vert_fov; }
+ void setFov( float horiz_fov, float vert_fov ) { _horiz_fov = horiz_fov;
_vert_fov = vert_fov; }
///update vertical fov based on window aspect and current horizontal fov
- inline void setAspect( float aspect ) {
+ void setAspect( float aspect ) {
//std::cout << "aspect: " << aspect << " vert: " << _vert_fov << " => "
<< aspect * _vert_fov << std::endl;
//_vert_fov = aspect / _horiz_fov;
_aspect = aspect;
}
- inline void setYaw( float yaw ) { _yaw = yaw; }
- inline float horizFov( void ) const { return _horiz_fov; }
- inline float vertFov( void ) const { return _vert_fov; }
- inline void addYaw( float yaw ) { _yaw += yaw; }
- inline void setPitch( float pitch ) { _pitch = pitch; }
- inline void addPitch( float pitch ) { _pitch += pitch; if( _pitch < 0 )
_pitch = 0; else if( _pitch > 180 ) _pitch = 180; }
+ void setYaw( float yaw ) { _yaw = yaw; }
+ float horizFov( void ) const { return _horiz_fov; }
+ float vertFov( void ) const { return _vert_fov; }
+ void addYaw( float yaw ) { _yaw += yaw; }
+ void setPitch( float pitch ) { _pitch = pitch; }
+ void addPitch( float pitch ) { _pitch += pitch; if( _pitch < 0 ) _pitch =
0; else if( _pitch > 180 ) _pitch = 180; }
- inline float realDistance( float z_buf_val ) const {
+ float realDistance( float z_buf_val ) const {
//formula found at http://www.cs.unc.edu/~hoff/techrep/openglz.html
//Z = Zn*Zf / (Zf - z*(Zf-Zn))
return _z_near * _z_far / ( _z_far - z_buf_val * ( _z_far - _z_near ) );
}
- inline void scroll( float dy ) { _z += dy; }
- inline float nearClip( void ) const { return _z_near; }
- inline float farClip( void ) const { return _z_far; }
- inline void setClip( float near, float far ) { _z_far = far; _z_near =
near; }
+ void scroll( float dy ) { _z += dy; }
+ float nearClip( void ) const { return _z_near; }
+ float farClip( void ) const { return _z_far; }
+ void setClip( float near, float far ) { _z_far = far; _z_near = near; }
- inline void reset() { setPitch( 70 ); setYaw( 0 ); }
+ void reset() { setPitch( 70 ); setYaw( 0 ); }
void Load( Worldfile* wf, int sec );
void Save( Worldfile* wf, int sec );
@@ -1284,10 +1285,10 @@
virtual void SetProjection( void ) const;
void move( float x, float y );
- inline void setYaw( float yaw ) { _yaw = yaw; }
- inline void setPitch( float pitch ) { _pitch = pitch; }
- inline void addYaw( float yaw ) { _yaw += yaw; }
- inline void addPitch( float pitch ) {
+ void setYaw( float yaw ) { _yaw = yaw; }
+ void setPitch( float pitch ) { _pitch = pitch; }
+ void addYaw( float yaw ) { _yaw += yaw; }
+ void addPitch( float pitch ) {
_pitch += pitch;
if( _pitch > 90 )
_pitch = 90;
@@ -1295,13 +1296,13 @@
_pitch = 0;
}
- inline void setScale( float scale ) { _scale = scale; }
- inline void setPose( float x, float y) { _x = x; _y = y; }
+ void setScale( float scale ) { _scale = scale; }
+ void setPose( float x, float y) { _x = x; _y = y; }
void scale( float scale, float shift_x = 0, float h = 0, float shift_y =
0, float w = 0 );
- inline void reset( void ) { _pitch = _yaw = 0; }
+ void reset( void ) { _pitch = _yaw = 0; }
- inline float scale() const { return _scale; }
+ float scale() const { return _scale; }
void Load( Worldfile* wf, int sec );
void Save( Worldfile* wf, int sec );
@@ -1376,7 +1377,7 @@
virtual void UnLoad();
virtual bool Save( const char* filename );
- inline virtual bool IsGUI() { return true; }
+ virtual bool IsGUI() { return true; }
virtual Model* RecentlySelectedModel();
@@ -1678,7 +1679,7 @@
void MapWithChildren();
void UnMapWithChildren();
- int TreeToPtrArray( GPtrArray* array );
+ int TreeToPtrArray( GPtrArray* array ) const;
/** raytraces a single ray from the point and heading identified by
pose, in local coords */
@@ -1731,7 +1732,7 @@
Model* ConditionalMove( Pose newpose );
- stg_meters_t ModelHeight();
+ stg_meters_t ModelHeight() const;
bool UpdateDue( void );
void UpdateIfDue();
@@ -1790,7 +1791,7 @@
virtual void PopColor(){ world->PopColor(); }
- PowerPack* FindPowerPack();
+ PowerPack* FindPowerPack() const;
void RecordRenderPoint( GSList** head, GSList* link,
unsigned int* c1, unsigned int* c2 );
@@ -1848,7 +1849,7 @@
void PushFlag( Flag* flag );
Flag* PopFlag();
- int GetFlagCount(){ return g_list_length( flag_list ); }
+ int GetFlagCount() const { return g_list_length( flag_list ); }
/** Add a pointer to a blinkenlight to the model. */
void AddBlinkenlight( stg_blinkenlight_t* b )
@@ -1892,33 +1893,33 @@
/** Returns a pointer to this model's parent model, or NULL if this
model has no parent */
- Model* Parent(){ return this->parent; }
+ Model* Parent() const { return this->parent; }
- Model* GetModel( const char* name );
+ Model* GetModel( const char* name ) const;
//int GuiMask(){ return this->gui_mask; };
/** Returns a pointer to the world that contains this model */
- World* GetWorld(){ return this->world; }
+ World* GetWorld() const { return this->world; }
/** return the root model of the tree containing this model */
Model* Root(){ return( parent ? parent->Root() : this ); }
- bool IsAntecedent( Model* testmod );
+ bool IsAntecedent( const Model* testmod ) const;
/** returns true if model [testmod] is a descendent of this model */
- bool IsDescendent( Model* testmod );
+ bool IsDescendent( const Model* testmod ) const;
/** returns true if model [testmod] is a descendent or antecedent of
this model */
- bool IsRelated( Model* testmod );
+ bool IsRelated( const Model* testmod ) const;
/** get the pose of a model in the global CS */
- Pose GetGlobalPose();
+ Pose GetGlobalPose() const;
/** get the velocity of a model in the global CS */
- Velocity GetGlobalVelocity();
+ Velocity GetGlobalVelocity() const;
/* set the velocity of a model in the global coordinate system */
- void SetGlobalVelocity( Velocity gvel );
+ void SetGlobalVelocity( const Velocity& gvel );
/** subscribe to a model's data */
void Subscribe();
@@ -1927,54 +1928,55 @@
void Unsubscribe();
/** set the pose of model in global coordinates */
- void SetGlobalPose( Pose gpose );
+ void SetGlobalPose( const Pose& gpose );
/** set a model's velocity in its parent's coordinate system */
- void SetVelocity( Velocity vel );
+ void SetVelocity( const Velocity& vel );
/** set a model's pose in its parent's coordinate system */
- void SetPose( Pose pose );
+ void SetPose( const Pose& pose );
/** add values to a model's pose in its parent's coordinate system */
- void AddToPose( Pose pose );
+ void AddToPose( const Pose& pose );
/** add values to a model's pose in its parent's coordinate system */
void AddToPose( double dx, double dy, double dz, double da );
/** set a model's geometry (size and center offsets) */
- void SetGeom( Geom src );
+ void SetGeom( const Geom& src );
/** Set a model's fiducial return value. Values less than zero
are not detected by the fiducial sensor. */
void SetFiducialReturn( int fid );
/** Get a model's fiducial return value. */
- int GetFiducialReturn()
- { return vis.fiducial_return; }
+ int GetFiducialReturn() const { return vis.fiducial_return; }
/** set a model's fiducial key: only fiducial finders with a
matching key can detect this model as a fiducial. */
void SetFiducialKey( int key );
- stg_color_t GetColor(){ return color; }
+ stg_color_t GetColor() const { return color; }
/** return a model's unique process-wide identifier */
- uint32_t GetId() { return id; }
+ uint32_t GetId() const { return id; }
// stg_laser_return_t GetLaserReturn(){ return laser_return; }
/** Change a model's parent - experimental*/
int SetParent( Model* newparent);
- /** Get a model's geometry - it's size and local pose (offset from
- origin in local coords) */
- Geom GetGeom(){ return geom; }
+ /** Get (a copy of) the model's geometry - it's size and local
+ pose (offset from origin in local coords). */
+ Geom GetGeom() const { return geom; }
- /** Get the pose of a model in its parent's coordinate system */
- Pose GetPose(){ return pose; }
+ /** Get (a copy of) the pose of a model in its parent's coordinate
+ system. */
+ Pose GetPose() const { return pose; }
- /** Get a model's velocity (in its local reference frame) */
- Velocity GetVelocity(){ return velocity; }
+ /** Get (a copy of) the model's velocity in its local reference
+ frame. */
+ Velocity GetVelocity() const { return velocity; }
// guess what these do?
void SetColor( stg_color_t col );
@@ -1993,7 +1995,7 @@
void SetWatts( stg_watts_t watts );
void SetMapResolution( stg_meters_t res );
- bool DataIsFresh(){ return this->data_fresh; }
+ bool DataIsFresh() const { return this->data_fresh; }
/* attach callback functions to data members. The function gets
called when the member is changed using SetX() accessor method
*/
@@ -2042,10 +2044,10 @@
/** named-property interface
*/
- void* GetProperty( const char* key );
- bool GetPropertyFloat( const char* key, float* f, float defaultval );
- bool GetPropertyInt( const char* key, int* i, int defaultval );
- bool GetPropertyStr( const char* key, char** c, char* defaultval );
+ void* GetProperty( const char* key ) const;
+ bool GetPropertyFloat( const char* key, float* f, float defaultval )
const;
+ bool GetPropertyInt( const char* key, int* i, int defaultval ) const;
+ bool GetPropertyStr( const char* key, char** c, char* defaultval )
const;
/** @brief Set a named property of a Stage model.
@@ -2084,25 +2086,24 @@
void UnsetProperty( const char* key );
- virtual void Print( char* prefix );
- virtual const char* PrintWithPose();
+ virtual void Print( char* prefix ) const;
+ virtual const char* PrintWithPose() const;
- /** Convert a pose in the world coordinate system into a model's
- local coordinate system. Overwrites [pose] with the new
- coordinate. */
- Pose GlobalToLocal( const Pose pose );
-
+ /** Given a global pose, returns that pose in the model's local
+ coordinate system. */
+ Pose GlobalToLocal( const Pose& pose ) const;
+
/** Return the global pose (i.e. pose in world coordinates) of a
pose specified in the model's local coordinate system */
- Pose LocalToGlobal( const Pose pose );
+ Pose LocalToGlobal( const Pose& pose ) const;
/** Return the 3d point in world coordinates of a 3d point
specified in the model's local coordinate system */
- stg_point3_t LocalToGlobal( const stg_point3_t local );
+ stg_point3_t LocalToGlobal( const stg_point3_t local ) const;
/** returns the first descendent of this model that is unsubscribed
and has the type indicated by the string */
- Model* GetUnsubscribedModelOfType( const stg_model_type_t type );
+ Model* GetUnsubscribedModelOfType( const stg_model_type_t type ) const;
/** returns the first descendent of this model that is unused
and has the type indicated by the string. This model is
tagged as used. */
@@ -2110,7 +2111,7 @@
/** Returns the value of the model's stall boolean, which is true
iff the model has crashed into another model */
- bool Stalled(){ return this->stall; }
+ bool Stalled() const { return this->stall; }
};
@@ -2568,25 +2569,25 @@
virtual void DataVisualize( Camera* cam );
///width of captured image
- inline int getWidth( void ) const { return _width; }
+ int getWidth( void ) const { return _width; }
///height of captured image
- inline int getHeight( void ) const { return _height; }
+ int getHeight( void ) const { return _height; }
///get reference to camera used
- inline const PerspectiveCamera& getCamera( void ) const { return
_camera; }
+ const PerspectiveCamera& getCamera( void ) const { return _camera; }
///get a reference to camera depth buffer
- inline const GLfloat* FrameDepth() const { return _frame_data; }
+ const GLfloat* FrameDepth() const { return _frame_data; }
///get a reference to camera color image. 3 bytes (RGB) per pixel
- inline const GLubyte* FrameColor() const { return _frame_color_data; }
+ const GLubyte* FrameColor() const { return _frame_color_data; }
///change the pitch
- inline void setPitch( float pitch ) { _pitch_offset = pitch;
_valid_vertexbuf_cache = false; }
+ void setPitch( float pitch ) { _pitch_offset = pitch;
_valid_vertexbuf_cache = false; }
///change the yaw
- inline void setYaw( float yaw ) { _yaw_offset = yaw;
_valid_vertexbuf_cache = false; }
+ void setYaw( float yaw ) { _yaw_offset = yaw; _valid_vertexbuf_cache
= false; }
};
// POSITION MODEL --------------------------------------------------------
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit