Revision: 6765 http://playerstage.svn.sourceforge.net/playerstage/?rev=6765&view=rev Author: rtv Date: 2008-07-04 15:58:26 -0700 (Fri, 04 Jul 2008)
Log Message: ----------- fixed model name prefix and window title bar Modified Paths: -------------- code/stage/trunk/libstage/CMakeLists.txt code/stage/trunk/libstage/ancestor.cc code/stage/trunk/libstage/canvas.cc code/stage/trunk/libstage/model_laser.cc code/stage/trunk/libstage/model_load.cc code/stage/trunk/libstage/model_position.cc code/stage/trunk/libstage/stage.cc code/stage/trunk/libstage/stest.cc code/stage/trunk/libstage/test.cc code/stage/trunk/libstage/world.cc code/stage/trunk/libstage/worldfile.cc code/stage/trunk/libstage/worldfile.hh code/stage/trunk/libstage/worldgui.cc Modified: code/stage/trunk/libstage/CMakeLists.txt =================================================================== --- code/stage/trunk/libstage/CMakeLists.txt 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/CMakeLists.txt 2008-07-04 22:58:26 UTC (rev 6765) @@ -65,6 +65,9 @@ add_executable( test test.cc ) target_link_libraries( test stage ) +add_executable( stest stest.cc ) +target_link_libraries( stest stage ) + INSTALL(TARGETS stagebinary stage RUNTIME DESTINATION bin LIBRARY DESTINATION lib Modified: code/stage/trunk/libstage/ancestor.cc =================================================================== --- code/stage/trunk/libstage/ancestor.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/ancestor.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -28,9 +28,17 @@ // poke a name into the child char* buf = new char[TOKEN_MAX]; - snprintf( buf, TOKEN_MAX, "%s.%s:%d", - token, typetable[mod->type].token, child_type_counts[mod->type] ); - + + if( token ) // if this object has a name, use it + snprintf( buf, TOKEN_MAX, "%s.%s:%d", + token, + typetable[mod->type].token, + child_type_counts[mod->type] ); + else + snprintf( buf, TOKEN_MAX, "%s:%d", + typetable[mod->type].token, + child_type_counts[mod->type] ); + //printf( "%s generated a name for my child %s\n", token, buf ); mod->SetToken( buf ); Modified: code/stage/trunk/libstage/canvas.cc =================================================================== --- code/stage/trunk/libstage/canvas.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/canvas.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -275,50 +275,52 @@ return 1; case FL_PUSH: // button pressed - StgModel* mod = getModel( startx, starty ); - startx = Fl::event_x(); - starty = Fl::event_y(); - selectedModel = false; - switch( Fl::event_button() ) + { + StgModel* mod = getModel( startx, starty ); + startx = Fl::event_x(); + starty = Fl::event_y(); + selectedModel = false; + switch( Fl::event_button() ) + { + case 1: + if( mod ) { + // clicked a model + if ( Fl::event_state( FL_SHIFT ) ) { + // holding shift, toggle selection + if ( selected( mod ) ) + unSelect( mod ); + else { + select( mod ); + selectedModel = true; // selected a model + } + } + else { + if ( !selected( mod ) ) { + // clicked on an unselected model while + // not holding shift, this is the new + // selection + unSelectAll(); + select( mod ); + } + selectedModel = true; // selected a model + } + } + else { + // clicked on empty space, unselect all + unSelectAll(); + } + return 1; + case 3: { - case 1: - if( mod ) { - // clicked a model - if ( Fl::event_state( FL_SHIFT ) ) { - // holding shift, toggle selection - if ( selected( mod ) ) - unSelect( mod ); - else { - select( mod ); - selectedModel = true; // selected a model - } - } - else { - if ( !selected( mod ) ) { - // clicked on an unselected model while - // not holding shift, this is the new - // selection - unSelectAll(); - select( mod ); - } - selectedModel = true; // selected a model - } - } - else { - // clicked on empty space, unselect all - unSelectAll(); - } - return 1; - case 3: - { - // leave selections alone - // rotating handled within FL_DRAG - return 1; + // leave selections alone + // rotating handled within FL_DRAG + return 1; } - default: - return 0; - } - + default: + return 0; + } + } + case FL_DRAG: // mouse moved while button was pressed { int dx = Fl::event_x() - startx; @@ -964,7 +966,6 @@ glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT ); } - if( perspectiveCam == true ) { if( showFollow && last_selection ) { Modified: code/stage/trunk/libstage/model_laser.cc =================================================================== --- code/stage/trunk/libstage/model_laser.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/model_laser.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -77,11 +77,11 @@ */ StgModelLaser::StgModelLaser( StgWorld* world, - StgModel* parent ) + StgModel* parent ) : StgModel( world, parent, MODEL_TYPE_LASER ) { PRINT_DEBUG2( "Constructing StgModelLaser %d (%s)\n", - id, typestr ); + id, typestr ); // sensible laser defaults interval = DEFAULT_INTERVAL_MS * (int)thousand; @@ -157,8 +157,8 @@ } static bool laser_raytrace_match( StgBlock* testblock, - StgModel* finder, - const void* dummy ) + StgModel* finder, + const void* dummy ) { // Ignore the model that's looking and things that are invisible to // lasers @@ -188,20 +188,20 @@ rayorg.a = bearing; Raytrace( rayorg, - range_max, - laser_raytrace_match, - NULL, - &sample, - true ); // z testing enabled + range_max, + laser_raytrace_match, + NULL, + &sample, + true ); // z testing enabled samples[t].range = sample.range; // if we hit a model and it reflects brightly, we set // reflectance high, else low if( sample.block && ( sample.block->Model()->GetLaserReturn() >= LaserBright ) ) - samples[t].reflectance = 1; + samples[t].reflectance = 1; else - samples[t].reflectance = 0; + samples[t].reflectance = 0; // todo - lower bound on range bearing += sample_incr; @@ -211,22 +211,22 @@ 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 - memcpy( &samples[t-g], - &samples[t-resolution], - sizeof(stg_laser_sample_t)); + // copy the rightmost sample data into this point + memcpy( &samples[t-g], + &samples[t-resolution], + sizeof(stg_laser_sample_t)); - 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); + } } data_dirty = true; @@ -310,7 +310,7 @@ if ( ! (showLaserData || showLaserStrikes) ) return; - glPushMatrix(); + glPushMatrix(); // we only regenerate the list if there's new data if( 1 /* (temp hack) data_dirty*/ ) @@ -318,17 +318,14 @@ data_dirty = false; glNewList( data_dl, GL_COMPILE ); - //glEnableClientState( GL_VERTEX_ARRAY ); + //glEnableClientState( GL_VERTEX_ARRAY ); glTranslatef( 0,0, geom.size.z/2.0 ); // shoot the laser beam out at the right height - - PushColor( 0, 0, 1, 0.5 ); - - glPointSize( 4.0 ); - - // DEBUG - draw the origin of the laser beams - glBegin( GL_POINTS ); - glVertex2f( 0,0 ); - glEnd(); + + // DEBUG - draw the origin of the laser beams + //glPointSize( 4.0 ); + //glBegin( GL_POINTS ); + //glVertex2f( 0,0 ); + //glEnd(); // pack the laser hit points into a vertex array for fast rendering static float* pts = NULL; @@ -337,59 +334,48 @@ pts[0] = 0.0; pts[1] = 0.0; - - glVertexPointer( 2, GL_FLOAT, 0, pts ); - + PushColor( 0, 0, 1, 0.5 ); + for( unsigned int s=0; s<sample_count; s++ ) - { - double ray_angle = (s * (fov / (sample_count-1))) - 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 * (fov / (sample_count-1))) - 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(); - - // why doesn't this work? - //glDrawArrays( GL_POINTS, 2*s+2, 1 ); - } + // 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(); + } - } + } PopColor(); - glDepthMask( GL_FALSE ); glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); // draw the filled polygon in transparent blue - PushColor( 0, 0, 1, 0.1 ); - - + PushColor( 0, 0, 1, 0.1 ); + glVertexPointer( 2, GL_FLOAT, 0, pts ); glDrawArrays( GL_POLYGON, 0, sample_count+1 ); - - // reset PopColor(); - if( showLaserStrikes ) - { - // draw the beam strike points in black - PushColor( 0, 0, 0, 1.0 ); - glPointSize( 1.0 ); - glDrawArrays( GL_POINTS, 0, sample_count+1 ); - PopColor(); - } + if( showLaserStrikes ) + { + // draw the beam strike points in black + PushColor( 0, 0, 0, 1.0 ); + glPointSize( 1.0 ); + glDrawArrays( GL_POINTS, 0, sample_count+1 ); + PopColor(); + } glDepthMask( GL_TRUE ); - - - //glDisableClientState( GL_VERTEX_ARRAY ); glEndList(); } // end if ( data_dirty ) glCallList( data_dl ); - glPopMatrix(); + glPopMatrix(); } Modified: code/stage/trunk/libstage/model_load.cc =================================================================== --- code/stage/trunk/libstage/model_load.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/model_load.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -1,19 +1,14 @@ #ifndef _GNU_SOURCE #define _GNU_SOURCE #endif + #include <limits.h> #include <libgen.h> // for dirname() #include <string.h> -#include "stage_internal.hh" - -//#define DEBUG 1 - #include <ltdl.h> -void FooInit( StgModel* ); -void FooUpdate( StgModel* ); +#include "stage_internal.hh" - void StgModel::Load() { assert( wf ); @@ -21,349 +16,349 @@ PRINT_DEBUG1( "Model \"%s\" loading...", token ); - if( wf->PropertyExists( wf_entity, "debug" ) ) + if( wf->PropertyExists( wf_entity, "debug" ) ) + { + PRINT_WARN2( "debug property specified for model %d %s\n", + wf_entity, this->token ); + this->debug = wf->ReadInt( wf_entity, "debug", this->debug ); + } + + if( wf->PropertyExists( wf_entity, "name" ) ) + { + char *name = (char*)wf->ReadString(wf_entity, "name", NULL ); + if( name ) { - PRINT_WARN2( "debug property specified for model %d %s\n", - wf_entity, this->token ); - this->debug = wf->ReadInt( wf_entity, "debug", this->debug ); + //printf( "changed %s to %s\n", this->token, token ); + this->token = strdup( name ); + world->AddModel( this ); // add this name to the world's table } + else + PRINT_ERR1( "Name blank for model %s. Check your worldfile\n", this->token ); - if( wf->PropertyExists( wf_entity, "name" ) ) - { - char *name = (char*)wf->ReadString(wf_entity, "name", NULL ); - if( name ) - { - //printf( "changed %s to %s\n", this->token, token ); - this->token = strdup( name ); - world->AddModel( this ); // add this name to the world's table - } - else - PRINT_ERR1( "Name blank for model %s. Check your worldfile\n", this->token ); + // add this name to the table - // add this name to the table + } - } + //PRINT_WARN1( "%s::Load", token ); - //PRINT_WARN1( "%s::Load", token ); + if( wf->PropertyExists( wf_entity, "origin" ) ) + { + stg_geom_t geom = GetGeom(); + geom.pose.x = wf->ReadTupleLength(wf_entity, "origin", 0, geom.pose.x ); + geom.pose.y = wf->ReadTupleLength(wf_entity, "origin", 1, geom.pose.y ); + geom.pose.a = wf->ReadTupleAngle(wf_entity, "origin", 2, geom.pose.a ); + this->SetGeom( geom ); + } - if( wf->PropertyExists( wf_entity, "origin" ) ) - { - stg_geom_t geom = GetGeom(); - geom.pose.x = wf->ReadTupleLength(wf_entity, "origin", 0, geom.pose.x ); - geom.pose.y = wf->ReadTupleLength(wf_entity, "origin", 1, geom.pose.y ); - geom.pose.a = wf->ReadTupleAngle(wf_entity, "origin", 2, geom.pose.a ); - this->SetGeom( geom ); - } + if( wf->PropertyExists( wf_entity, "origin4" ) ) + { + stg_geom_t geom = GetGeom(); + geom.pose.x = wf->ReadTupleLength(wf_entity, "origin4", 0, geom.pose.x ); + geom.pose.y = wf->ReadTupleLength(wf_entity, "origin4", 1, geom.pose.y ); + geom.pose.z = wf->ReadTupleLength(wf_entity, "origin4", 2, geom.pose.z ); + geom.pose.a = wf->ReadTupleAngle(wf_entity, "origin4", 3, geom.pose.a ); + this->SetGeom( geom ); + } - if( wf->PropertyExists( wf_entity, "origin4" ) ) - { - stg_geom_t geom = GetGeom(); - geom.pose.x = wf->ReadTupleLength(wf_entity, "origin4", 0, geom.pose.x ); - geom.pose.y = wf->ReadTupleLength(wf_entity, "origin4", 1, geom.pose.y ); - geom.pose.z = wf->ReadTupleLength(wf_entity, "origin4", 2, geom.pose.z ); - geom.pose.a = wf->ReadTupleAngle(wf_entity, "origin4", 3, geom.pose.a ); - this->SetGeom( geom ); - } + if( wf->PropertyExists( wf_entity, "size" ) ) + { + stg_geom_t geom = GetGeom(); + geom.size.x = wf->ReadTupleLength(wf_entity, "size", 0, geom.size.x ); + geom.size.y = wf->ReadTupleLength(wf_entity, "size", 1, geom.size.y ); + this->SetGeom( geom ); + } - if( wf->PropertyExists( wf_entity, "size" ) ) - { - stg_geom_t geom = GetGeom(); - geom.size.x = wf->ReadTupleLength(wf_entity, "size", 0, geom.size.x ); - geom.size.y = wf->ReadTupleLength(wf_entity, "size", 1, geom.size.y ); - this->SetGeom( geom ); - } + if( wf->PropertyExists( wf_entity, "size3" ) ) + { + stg_geom_t geom = GetGeom(); + geom.size.x = wf->ReadTupleLength(wf_entity, "size3", 0, geom.size.x ); + geom.size.y = wf->ReadTupleLength(wf_entity, "size3", 1, geom.size.y ); + geom.size.z = wf->ReadTupleLength(wf_entity, "size3", 2, geom.size.z ); + this->SetGeom( geom ); + } - if( wf->PropertyExists( wf_entity, "size3" ) ) - { - stg_geom_t geom = GetGeom(); - geom.size.x = wf->ReadTupleLength(wf_entity, "size3", 0, geom.size.x ); - geom.size.y = wf->ReadTupleLength(wf_entity, "size3", 1, geom.size.y ); - geom.size.z = wf->ReadTupleLength(wf_entity, "size3", 2, geom.size.z ); - this->SetGeom( geom ); - } + if( wf->PropertyExists( wf_entity, "pose" )) + { + stg_pose_t pose = GetPose(); + pose.x = wf->ReadTupleLength(wf_entity, "pose", 0, pose.x ); + pose.y = wf->ReadTupleLength(wf_entity, "pose", 1, pose.y ); + pose.a = wf->ReadTupleAngle(wf_entity, "pose", 2, pose.a ); + this->SetPose( pose ); + } - if( wf->PropertyExists( wf_entity, "pose" )) - { - stg_pose_t pose = GetPose(); - pose.x = wf->ReadTupleLength(wf_entity, "pose", 0, pose.x ); - pose.y = wf->ReadTupleLength(wf_entity, "pose", 1, pose.y ); - pose.a = wf->ReadTupleAngle(wf_entity, "pose", 2, pose.a ); - this->SetPose( pose ); - } + if( wf->PropertyExists( wf_entity, "pose4" )) + { + stg_pose_t pose = GetPose(); + pose.x = wf->ReadTupleLength(wf_entity, "pose4", 0, pose.x ); + pose.y = wf->ReadTupleLength(wf_entity, "pose4", 1, pose.y ); + pose.z = wf->ReadTupleLength(wf_entity, "pose4", 2, pose.z ); + pose.a = wf->ReadTupleAngle( wf_entity, "pose4", 3, pose.a ); - if( wf->PropertyExists( wf_entity, "pose4" )) - { - stg_pose_t pose = GetPose(); - pose.x = wf->ReadTupleLength(wf_entity, "pose4", 0, pose.x ); - pose.y = wf->ReadTupleLength(wf_entity, "pose4", 1, pose.y ); - pose.z = wf->ReadTupleLength(wf_entity, "pose4", 2, pose.z ); - pose.a = wf->ReadTupleAngle( wf_entity, "pose4", 3, pose.a ); + this->SetPose( pose ); + } - this->SetPose( pose ); - } + if( wf->PropertyExists( wf_entity, "velocity" )) + { + stg_velocity_t vel = GetVelocity(); + vel.x = wf->ReadTupleLength(wf_entity, "velocity", 0, vel.x ); + vel.y = wf->ReadTupleLength(wf_entity, "velocity", 1, vel.y ); + vel.a = wf->ReadTupleAngle(wf_entity, "velocity", 3, vel.a ); + this->SetVelocity( vel ); - if( wf->PropertyExists( wf_entity, "velocity" )) - { - stg_velocity_t vel = GetVelocity(); - vel.x = wf->ReadTupleLength(wf_entity, "velocity", 0, vel.x ); - vel.y = wf->ReadTupleLength(wf_entity, "velocity", 1, vel.y ); - vel.a = wf->ReadTupleAngle(wf_entity, "velocity", 3, vel.a ); - this->SetVelocity( vel ); + if( vel.x || vel.y || vel.z || vel.a ) + world->StartUpdatingModel( this ); + } - if( vel.x || vel.y || vel.z || vel.a ) - world->StartUpdatingModel( this ); - } + if( wf->PropertyExists( wf_entity, "velocity4" )) + { + stg_velocity_t vel = GetVelocity(); + vel.x = wf->ReadTupleLength(wf_entity, "velocity4", 0, vel.x ); + vel.y = wf->ReadTupleLength(wf_entity, "velocity4", 1, vel.y ); + vel.z = wf->ReadTupleLength(wf_entity, "velocity4", 2, vel.z ); + vel.a = wf->ReadTupleAngle(wf_entity, "velocity4", 3, vel.a ); + this->SetVelocity( vel ); + } - if( wf->PropertyExists( wf_entity, "velocity4" )) - { - stg_velocity_t vel = GetVelocity(); - vel.x = wf->ReadTupleLength(wf_entity, "velocity4", 0, vel.x ); - vel.y = wf->ReadTupleLength(wf_entity, "velocity4", 1, vel.y ); - vel.z = wf->ReadTupleLength(wf_entity, "velocity4", 2, vel.z ); - vel.a = wf->ReadTupleAngle(wf_entity, "velocity4", 3, vel.a ); - this->SetVelocity( vel ); - } + if( wf->PropertyExists( wf_entity, "boundary" )) + { + this->SetBoundary( wf->ReadInt(wf_entity, "boundary", this->boundary )); + } - if( wf->PropertyExists( wf_entity, "boundary" )) + if( wf->PropertyExists( wf_entity, "color" )) + { + stg_color_t col = 0xFFFF0000; // red; + const char* colorstr = wf->ReadString( wf_entity, "color", NULL ); + if( colorstr ) { - this->SetBoundary( wf->ReadInt(wf_entity, "boundary", this->boundary )); - } + if( strcmp( colorstr, "random" ) == 0 ) + { + col = (uint32_t)random(); + col |= 0xFF000000; // set the alpha channel to max + } + else + col = stg_lookup_color( colorstr ); - if( wf->PropertyExists( wf_entity, "color" )) - { - stg_color_t col = 0xFFFF0000; // red; - const char* colorstr = wf->ReadString( wf_entity, "color", NULL ); - if( colorstr ) - { - if( strcmp( colorstr, "random" ) == 0 ) - { - col = (uint32_t)random(); - col |= 0xFF000000; // set the alpha channel to max - } - else - col = stg_lookup_color( colorstr ); + this->SetColor( col ); + } + } - this->SetColor( col ); - } - } + if( wf->PropertyExists( wf_entity, "color_rgba" )) + { + double red = wf->ReadTupleFloat( wf_entity, "color_rgba", 0, 0); + double green = wf->ReadTupleFloat( wf_entity, "color_rgba", 1, 0); + double blue = wf->ReadTupleFloat( wf_entity, "color_rgba", 2, 0); + double alpha = wf->ReadTupleFloat( wf_entity, "color_rgba", 3, 0); - if( wf->PropertyExists( wf_entity, "color_rgba" )) - { - double red = wf->ReadTupleFloat( wf_entity, "color_rgba", 0, 0); - double green = wf->ReadTupleFloat( wf_entity, "color_rgba", 1, 0); - double blue = wf->ReadTupleFloat( wf_entity, "color_rgba", 2, 0); - double alpha = wf->ReadTupleFloat( wf_entity, "color_rgba", 3, 0); + this->SetColor( stg_color_pack( red, green, blue, alpha )); + } - this->SetColor( stg_color_pack( red, green, blue, alpha )); - } + if( wf->PropertyExists( wf_entity, "bitmap" ) ) + { + const char* bitmapfile = wf->ReadString( wf_entity, "bitmap", NULL ); + assert( bitmapfile ); - if( wf->PropertyExists( wf_entity, "bitmap" ) ) + char full[_POSIX_PATH_MAX]; + + if( bitmapfile[0] == '/' ) + strcpy( full, bitmapfile ); + else { - const char* bitmapfile = wf->ReadString( wf_entity, "bitmap", NULL ); - assert( bitmapfile ); + char *tmp = strdup(wf->filename); + snprintf( full, _POSIX_PATH_MAX, + "%s/%s", dirname(tmp), bitmapfile ); + free(tmp); + } - char full[_POSIX_PATH_MAX]; + PRINT_DEBUG1( "attempting to load image %s", full ); - if( bitmapfile[0] == '/' ) - strcpy( full, bitmapfile ); - else - { - char *tmp = strdup(wf->filename); - snprintf( full, _POSIX_PATH_MAX, - "%s/%s", dirname(tmp), bitmapfile ); - free(tmp); - } - - PRINT_DEBUG1( "attempting to load image %s", full ); - - stg_rotrect_t* rects = NULL; - unsigned int rect_count = 0; - unsigned int width, height; - if( stg_rotrects_from_image_file( full, + stg_rotrect_t* rects = NULL; + unsigned int rect_count = 0; + unsigned int width, height; + if( stg_rotrects_from_image_file( full, &rects, &rect_count, &width, &height ) ) - { - PRINT_ERR1( "failed to load rects from image file \"%s\"", - full ); - return; - } + { + PRINT_ERR1( "failed to load rects from image file \"%s\"", + full ); + return; + } - this->UnMap(); - this->ClearBlocks(); + this->UnMap(); + this->ClearBlocks(); - //printf( "found %d rects\n", rect_count ); + //printf( "found %d rects\n", rect_count ); - if( rects && (rect_count > 0) ) - { - //puts( "loading rects" ); - for( unsigned int r=0; r<rect_count; r++ ) - this->AddBlockRect( rects[r].pose.x, rects[r].pose.y, - rects[r].size.x, rects[r].size.y ); + if( rects && (rect_count > 0) ) + { + //puts( "loading rects" ); + for( unsigned int r=0; r<rect_count; r++ ) + this->AddBlockRect( rects[r].pose.x, rects[r].pose.y, + rects[r].size.x, rects[r].size.y ); - if( this->boundary ) - { - // add thin bounding blocks - double epsilon = 0.01; - this->AddBlockRect(0,0, epsilon, height ); - this->AddBlockRect(0,0, width, epsilon ); - this->AddBlockRect(0, height-epsilon, width, epsilon ); - this->AddBlockRect(width-epsilon,0, epsilon, height ); - } + if( this->boundary ) + { + // add thin bounding blocks + double epsilon = 0.01; + this->AddBlockRect(0,0, epsilon, height ); + this->AddBlockRect(0,0, width, epsilon ); + this->AddBlockRect(0, height-epsilon, width, epsilon ); + this->AddBlockRect(width-epsilon,0, epsilon, height ); + } - StgBlock::ScaleList( this->blocks, &this->geom.size ); - this->Map(); - this->NeedRedraw(); + StgBlock::ScaleList( this->blocks, &this->geom.size ); + this->Map(); + this->NeedRedraw(); - g_free( rects ); - } + g_free( rects ); + } - //printf( "model %s block count %d\n", - // token, g_list_length( blocks )); - } + //printf( "model %s block count %d\n", + // token, g_list_length( blocks )); + } - if( wf->PropertyExists( wf_entity, "blocks" ) ) - { - int blockcount = wf->ReadInt( wf_entity, "blocks", -1 ); + if( wf->PropertyExists( wf_entity, "blocks" ) ) + { + int blockcount = wf->ReadInt( wf_entity, "blocks", -1 ); - this->UnMap(); - this->ClearBlocks(); + this->UnMap(); + this->ClearBlocks(); - //printf( "expecting %d blocks\n", blockcount ); + //printf( "expecting %d blocks\n", blockcount ); - char key[256]; - for( int l=0; l<blockcount; l++ ) - { - snprintf(key, sizeof(key), "block[%d].points", l); - int pointcount = wf->ReadInt(wf_entity,key,0); + char key[256]; + for( int l=0; l<blockcount; l++ ) + { + snprintf(key, sizeof(key), "block[%d].points", l); + int pointcount = wf->ReadInt(wf_entity,key,0); - //printf( "expecting %d points in block %d\n", - //pointcount, l ); + //printf( "expecting %d points in block %d\n", + //pointcount, l ); - stg_point_t* pts = stg_points_create( pointcount ); + stg_point_t* pts = stg_points_create( pointcount ); - int p; - for( p=0; p<pointcount; p++ ) { - snprintf(key, sizeof(key), "block[%d].point[%d]", l, p ); + int p; + for( p=0; p<pointcount; p++ ) { + snprintf(key, sizeof(key), "block[%d].point[%d]", l, p ); - pts[p].x = wf->ReadTupleLength(wf_entity, key, 0, 0); - pts[p].y = wf->ReadTupleLength(wf_entity, key, 1, 0); + pts[p].x = wf->ReadTupleLength(wf_entity, key, 0, 0); + pts[p].y = wf->ReadTupleLength(wf_entity, key, 1, 0); - //printf( "key %s x: %.2f y: %.2f\n", - // key, pt.x, pt.y ); - } + //printf( "key %s x: %.2f y: %.2f\n", + // key, pt.x, pt.y ); + } - // block Z axis - snprintf(key, sizeof(key), "block[%d].z", l); + // block Z axis + snprintf(key, sizeof(key), "block[%d].z", l); - stg_meters_t zmin = - wf->ReadTupleLength(wf_entity, key, 0, 0.0 ); + stg_meters_t zmin = + wf->ReadTupleLength(wf_entity, key, 0, 0.0 ); - stg_meters_t zmax = - wf->ReadTupleLength(wf_entity, key, 1, 1.0 ); + stg_meters_t zmax = + wf->ReadTupleLength(wf_entity, key, 1, 1.0 ); - // block color - stg_color_t blockcol = this->color; - bool inherit_color = true; + // block color + stg_color_t blockcol = this->color; + bool inherit_color = true; - snprintf(key, sizeof(key), "block[%d].color", l); + snprintf(key, sizeof(key), "block[%d].color", l); - const char* colorstr = wf->ReadString( wf_entity, key, NULL ); - if( colorstr ) - { - blockcol = stg_lookup_color( colorstr ); - inherit_color = false; - } + const char* colorstr = wf->ReadString( wf_entity, key, NULL ); + if( colorstr ) + { + blockcol = stg_lookup_color( colorstr ); + inherit_color = false; + } - this->AddBlock( pts, pointcount, zmin, zmax, blockcol, inherit_color ); + this->AddBlock( pts, pointcount, zmin, zmax, blockcol, inherit_color ); - stg_points_destroy( pts ); - } + stg_points_destroy( pts ); + } - StgBlock::ScaleList( this->blocks, &this->geom.size ); + StgBlock::ScaleList( this->blocks, &this->geom.size ); - if( this->boundary ) - { - // add thin bounding blocks - double epsilon = 0.001; - double width = geom.size.x; - double height = geom.size.y; - this->AddBlockRect(-width/2.0, -height/2.0, epsilon, height ); - this->AddBlockRect(-width/2.0, -height/2.0, width, epsilon ); - this->AddBlockRect(-width/2.0, height/2.0-epsilon, width, epsilon ); - this->AddBlockRect(width/2.0-epsilon, -height/2.0, epsilon, height ); - } + if( this->boundary ) + { + // add thin bounding blocks + double epsilon = 0.001; + double width = geom.size.x; + double height = geom.size.y; + this->AddBlockRect(-width/2.0, -height/2.0, epsilon, height ); + this->AddBlockRect(-width/2.0, -height/2.0, width, epsilon ); + this->AddBlockRect(-width/2.0, height/2.0-epsilon, width, epsilon ); + this->AddBlockRect(width/2.0-epsilon, -height/2.0, epsilon, height ); + } - this->Map(); - } + this->Map(); + } - if( wf->PropertyExists( wf_entity, "mass" )) - this->SetMass( wf->ReadFloat(wf_entity, "mass", this->mass )); + if( wf->PropertyExists( wf_entity, "mass" )) + this->SetMass( wf->ReadFloat(wf_entity, "mass", this->mass )); - if( wf->PropertyExists( wf_entity, "fiducial_return" )) - this->SetFiducialReturn( wf->ReadInt( wf_entity, "fiducial_return", this->fiducial_return )); + if( wf->PropertyExists( wf_entity, "fiducial_return" )) + this->SetFiducialReturn( wf->ReadInt( wf_entity, "fiducial_return", this->fiducial_return )); - if( wf->PropertyExists( wf_entity, "fiducial_key" )) - this->SetFiducialKey( wf->ReadInt( wf_entity, "fiducial_key", this->fiducial_key )); + if( wf->PropertyExists( wf_entity, "fiducial_key" )) + this->SetFiducialKey( wf->ReadInt( wf_entity, "fiducial_key", this->fiducial_key )); - if( wf->PropertyExists( wf_entity, "obstacle_return" )) - this->SetObstacleReturn( wf->ReadInt( wf_entity, "obstacle_return", this->obstacle_return )); + if( wf->PropertyExists( wf_entity, "obstacle_return" )) + this->SetObstacleReturn( wf->ReadInt( wf_entity, "obstacle_return", this->obstacle_return )); - if( wf->PropertyExists( wf_entity, "ranger_return" )) - this->SetRangerReturn( wf->ReadInt( wf_entity, "ranger_return", this->ranger_return )); + if( wf->PropertyExists( wf_entity, "ranger_return" )) + this->SetRangerReturn( wf->ReadInt( wf_entity, "ranger_return", this->ranger_return )); - if( wf->PropertyExists( wf_entity, "blob_return" )) - this->SetBlobReturn( wf->ReadInt( wf_entity, "blob_return", this->blob_return )); + if( wf->PropertyExists( wf_entity, "blob_return" )) + this->SetBlobReturn( wf->ReadInt( wf_entity, "blob_return", this->blob_return )); - if( wf->PropertyExists( wf_entity, "laser_return" )) - this->SetLaserReturn( (stg_laser_return_t)wf->ReadInt(wf_entity, "laser_return", this->laser_return )); + if( wf->PropertyExists( wf_entity, "laser_return" )) + this->SetLaserReturn( (stg_laser_return_t)wf->ReadInt(wf_entity, "laser_return", this->laser_return )); - if( wf->PropertyExists( wf_entity, "gripper_return" )) - this->SetGripperReturn( wf->ReadInt( wf_entity, "gripper_return", this->gripper_return )); + if( wf->PropertyExists( wf_entity, "gripper_return" )) + this->SetGripperReturn( wf->ReadInt( wf_entity, "gripper_return", this->gripper_return )); - if( wf->PropertyExists( wf_entity, "gui_nose" )) - this->SetGuiNose( wf->ReadInt(wf_entity, "gui_nose", this->gui_nose )); + if( wf->PropertyExists( wf_entity, "gui_nose" )) + this->SetGuiNose( wf->ReadInt(wf_entity, "gui_nose", this->gui_nose )); - if( wf->PropertyExists( wf_entity, "gui_grid" )) - this->SetGuiGrid( wf->ReadInt(wf_entity, "gui_grid", this->gui_grid )); + if( wf->PropertyExists( wf_entity, "gui_grid" )) + this->SetGuiGrid( wf->ReadInt(wf_entity, "gui_grid", this->gui_grid )); - if( wf->PropertyExists( wf_entity, "gui_outline" )) - this->SetGuiOutline( wf->ReadInt(wf_entity, "gui_outline", this->gui_outline )); + if( wf->PropertyExists( wf_entity, "gui_outline" )) + this->SetGuiOutline( wf->ReadInt(wf_entity, "gui_outline", this->gui_outline )); - if( wf->PropertyExists( wf_entity, "gui_movemask" )) - this->SetGuiMask( wf->ReadInt(wf_entity, "gui_movemask", this->gui_mask )); + if( wf->PropertyExists( wf_entity, "gui_movemask" )) + this->SetGuiMask( wf->ReadInt(wf_entity, "gui_movemask", this->gui_mask )); - if( wf->PropertyExists( wf_entity, "map_resolution" )) - this->SetMapResolution( wf->ReadFloat(wf_entity, "map_resolution", this->map_resolution )); + if( wf->PropertyExists( wf_entity, "map_resolution" )) + this->SetMapResolution( wf->ReadFloat(wf_entity, "map_resolution", this->map_resolution )); - if( wf->PropertyExists( wf_entity, "ctrl" )) - { - char* lib = (char*)wf->ReadString(wf_entity, "ctrl", NULL ); + if( wf->PropertyExists( wf_entity, "ctrl" )) + { + char* lib = (char*)wf->ReadString(wf_entity, "ctrl", NULL ); - if( !lib ) - puts( "Error - NULL library name" ); - else - LoadControllerModule( lib ); - } + if( !lib ) + puts( "Error - NULL library name" ); + else + LoadControllerModule( lib ); + } - if( wf->PropertyExists( wf_entity, "say" )) - this->Say( wf->ReadString(wf_entity, "say", NULL )); + if( wf->PropertyExists( wf_entity, "say" )) + this->Say( wf->ReadString(wf_entity, "say", NULL )); - // call any type-specific load callbacks - this->CallCallbacks( &this->load_hook ); + // call any type-specific load callbacks + this->CallCallbacks( &this->load_hook ); - // MUST BE THE LAST THING LOADED - if( wf->PropertyExists( wf_entity, "alwayson" )) - { - if( wf->ReadInt( wf_entity, "alwayson", 0) > 0 ) - Startup(); - } + // MUST BE THE LAST THING LOADED + if( wf->PropertyExists( wf_entity, "alwayson" )) + { + if( wf->ReadInt( wf_entity, "alwayson", 0) > 0 ) + Startup(); + } - if( this->debug ) - printf( "Model \"%s\" is in debug mode\n", token ); + if( this->debug ) + printf( "Model \"%s\" is in debug mode\n", token ); - PRINT_DEBUG1( "Model \"%s\" loading complete", token ); + PRINT_DEBUG1( "Model \"%s\" loading complete", token ); } @@ -372,70 +367,70 @@ assert( wf ); assert( wf_entity ); - PRINT_DEBUG1( "Model \"%s\" saving...", token ); + PRINT_DEBUG1( "Model \"%s\" saving...", token ); - PRINT_DEBUG4( "saving model %s pose %.2f %.2f %.2f", - this->token, - this->pose.x, - this->pose.y, - this->pose.a ); + PRINT_DEBUG4( "saving model %s pose %.2f %.2f %.2f", + this->token, + this->pose.x, + this->pose.y, + this->pose.a ); - // right now we only save poses - wf->WriteTupleLength( wf_entity, "pose", 0, this->pose.x); - wf->WriteTupleLength( wf_entity, "pose", 1, this->pose.y); - wf->WriteTupleAngle( wf_entity, "pose", 2, this->pose.a); + // right now we only save poses + wf->WriteTupleLength( wf_entity, "pose", 0, this->pose.x); + wf->WriteTupleLength( wf_entity, "pose", 1, this->pose.y); + wf->WriteTupleAngle( wf_entity, "pose", 2, this->pose.a); - wf->WriteTupleLength( wf_entity, "pose3", 0, this->pose.x); - wf->WriteTupleLength( wf_entity, "pose3", 1, this->pose.y); - wf->WriteTupleLength( wf_entity, "pose3", 2, this->pose.z); - wf->WriteTupleAngle( wf_entity, "pose3", 3, this->pose.a); + wf->WriteTupleLength( wf_entity, "pose3", 0, this->pose.x); + wf->WriteTupleLength( wf_entity, "pose3", 1, this->pose.y); + wf->WriteTupleLength( wf_entity, "pose3", 2, this->pose.z); + wf->WriteTupleAngle( wf_entity, "pose3", 3, this->pose.a); - // call any type-specific save callbacks - this->CallCallbacks( &this->save_hook ); + // call any type-specific save callbacks + this->CallCallbacks( &this->save_hook ); - PRINT_DEBUG1( "Model \"%s\" saving complete.", token ); + PRINT_DEBUG1( "Model \"%s\" saving complete.", token ); } void StgModel::LoadControllerModule( char* lib ) { - printf( "[Ctrl \"%s\"", lib ); - fflush(stdout); + printf( "[Ctrl \"%s\"", lib ); + fflush(stdout); - /* Initialise libltdl. */ - int errors = lt_dlinit(); - assert(errors==0); + /* Initialise libltdl. */ + int errors = lt_dlinit(); + assert(errors==0); - char* stagepath = getenv("STAGEPATH"); - if( stagepath == NULL ) - stagepath = "."; + char* stagepath = getenv("STAGEPATH"); + if( stagepath == NULL ) + stagepath = (char*)"."; - lt_dlsetsearchpath( stagepath ); + lt_dlsetsearchpath( stagepath ); - lt_dlhandle handle = NULL; + lt_dlhandle handle = NULL; - if(( handle = lt_dlopenext( lib ) )) - { - printf( "]" ); + if(( handle = lt_dlopenext( lib ) )) + { + printf( "]" ); - this->initfunc = (ctrlinit_t*)lt_dlsym( handle, "Init" ); - if( this->initfunc == NULL ) - { - printf( "Libtool error: %s. Something is wrong with your plugin. Quitting\n", - lt_dlerror() ); // report the error from libtool - exit(-1); - } - } - else + this->initfunc = (ctrlinit_t*)lt_dlsym( handle, "Init" ); + if( this->initfunc == NULL ) { - printf( "Libtool error: %s. Can't open your plugin controller. Quitting\n", - lt_dlerror() ); // report the error from libtool - - PRINT_ERR1( "Failed to open \"%s\". Check that it can be found by searching the directories in your STAGEPATH environment variable, or the current directory if STAGEPATH is not set.]\n", lib ); - exit(-1); + printf( "Libtool error: %s. Something is wrong with your plugin. Quitting\n", + lt_dlerror() ); // report the error from libtool + exit(-1); } + } + else + { + printf( "Libtool error: %s. Can't open your plugin controller. Quitting\n", + lt_dlerror() ); // report the error from libtool - fflush(stdout); + PRINT_ERR1( "Failed to open \"%s\". Check that it can be found by searching the directories in your STAGEPATH environment variable, or the current directory if STAGEPATH is not set.]\n", lib ); + exit(-1); + } + + fflush(stdout); } Modified: code/stage/trunk/libstage/model_position.cc =================================================================== --- code/stage/trunk/libstage/model_position.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/model_position.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -170,12 +170,11 @@ // specified est_origin = this->GetGlobalPose(); - keyword = "localization_origin"; if( wf->PropertyExists( wf_entity, keyword ) ) { - est_origin.x = wf->ReadTupleLength( wf_entity, keyword, 0, est_origin.x ); - est_origin.y = wf->ReadTupleLength( wf_entity, keyword, 1, est_origin.y ); - est_origin.a = wf->ReadTupleAngle( wf_entity,keyword, 2, est_origin.a ); + est_origin.x = wf->ReadTupleLength( wf_entity, "localization_origin", 0, est_origin.x ); + est_origin.y = wf->ReadTupleLength( wf_entity, "localization_origin", 1, est_origin.y ); + est_origin.a = wf->ReadTupleAngle( wf_entity, "localization_origin", 2, est_origin.a ); // compute our localization pose based on the origin and true pose stg_pose_t gpose = this->GetGlobalPose(); @@ -195,15 +194,14 @@ } // odometry model parameters - keyword = "odom_error"; if( wf->PropertyExists( wf_entity, keyword ) ) { integration_error.x = - wf->ReadTupleLength( wf_entity, keyword, 0, integration_error.x ); + wf->ReadTupleLength( wf_entity, "odom_error", 0, integration_error.x ); integration_error.y = - wf->ReadTupleLength( wf_entity, keyword, 1, integration_error.y ); + wf->ReadTupleLength( wf_entity, "odom_error", 1, integration_error.y ); integration_error.a - = wf->ReadTupleAngle( wf_entity, keyword, 2, integration_error.a ); + = wf->ReadTupleAngle( wf_entity, "odom_error", 2, integration_error.a ); } // choose a localization model Modified: code/stage/trunk/libstage/stage.cc =================================================================== --- code/stage/trunk/libstage/stage.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/stage.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -193,7 +193,7 @@ if( file == NULL ) { - char* searchfiles[] = { + const char* searchfiles[] = { "./rgb.txt", #ifdef RGBFILE RGBFILE, @@ -205,7 +205,7 @@ searchfiles[i]; i++ ) { - char* filename = searchfiles[i]; + const char* filename = searchfiles[i]; PRINT_DEBUG1( "Attempting to open \"%s\"", filename ); if( (file = fopen( filename, "r")) ) break; // opened a file ok - jump out of for loop Modified: code/stage/trunk/libstage/stest.cc =================================================================== --- code/stage/trunk/libstage/stest.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/stest.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -25,8 +25,8 @@ StgModelLaser* laser; StgModelPosition* position; StgModelRanger* ranger; - StgModelFiducial* fiducial; - StgModelBlobfinder* blobfinder; + //StgModelFiducial* fiducial; + //StgModelBlobfinder* blobfinder; } robot_t; #define VSPEED 0.4 // meters per second @@ -58,16 +58,16 @@ for( int i=0; i<POPSIZE; i++ ) { - char* base = "r"; + const char* base = "r"; sprintf( namebuf, "%s%d", base, i ); robots[i].position = (StgModelPosition*)world.GetModel( namebuf ); assert(robots[i].position); robots[i].position->Subscribe(); - robots[i].laser = (StgModelLaser*) - robots[i].position->GetUnsubscribedModelOfType( "laser" ); - assert(robots[i].laser); - robots[i].laser->Subscribe(); + // robots[i].laser = (StgModelLaser*) +// robots[i].position->GetUnsubscribedModelOfType( MODEL_TYPE_LASER ); +// assert(robots[i].laser); + //robots[i].laser->Subscribe(); // robots[i].fiducial = (StgModelFiducial*) // robots[i].position->GetUnsubscribedModelOfType( "fiducial" ); @@ -75,7 +75,7 @@ // robots[i].fiducial->Subscribe(); robots[i].ranger = (StgModelRanger*) - robots[i].position->GetUnsubscribedModelOfType( "ranger" ); + robots[i].position->GetUnsubscribedModelOfType( MODEL_TYPE_RANGER ); assert(robots[i].ranger); robots[i].ranger->Subscribe(); @@ -86,11 +86,10 @@ } // start the clock - //world.Start(); - //puts( "done" ); + //world.Start();readltime //puts( "done" ); - while( ! world.TestQuit() ) - if( world.RealTimeUpdate() ) + while( 1 ) + if( world.Update() ) // if( world.Update() ) for( int i=0; i<POPSIZE; i++ ) { Modified: code/stage/trunk/libstage/test.cc =================================================================== --- code/stage/trunk/libstage/test.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/test.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -14,13 +14,13 @@ wg->Update(); } -void test( char* str, double a, double b ) +void test( const char* str, double a, double b ) { if( fabs(a-b) > epsilon ) printf( "FAIL %s expected %.3f saw %.3f\n", str, a, b ); } -void test( char* str, stg_pose_t a, stg_pose_t b ) +void test( const char* str, stg_pose_t a, stg_pose_t b ) { if( fabs(a.x-b.x) > epsilon ) printf( "POSE FAIL %s expected pose.x %.3f saw pose.x %.3f\n", str, a.x, b.x ); Modified: code/stage/trunk/libstage/world.cc =================================================================== --- code/stage/trunk/libstage/world.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/world.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -449,145 +449,152 @@ stg_raytrace_sample_t* sample, bool ztest ) { + // printf( "raytracing at [ %.2f %.2f %.2f %.2f ] for %.2f \n", +// pose.x, +// pose.y, +// pose.z, +// pose.a, +// range ); + // initialize the sample - memcpy( &sample->pose, &pose, sizeof(stg_pose_t)); // pose stays fixed - sample->range = range; // we might change this below - sample->block = NULL; // we might change this below + sample->pose = pose; + sample->range = range; // we might change this below + sample->block = NULL; // we might change this below + + // find the global integer bitmap address of the ray + int32_t x = (int32_t)(pose.x*ppm); + int32_t y = (int32_t)(pose.y*ppm); + int32_t z = 0; + + int32_t xstart = x; + int32_t ystart = y; + + // and the x and y offsets of the ray + int32_t dx = (int32_t)(ppm*range * cos(pose.a)); + int32_t dy = (int32_t)(ppm*range * sin(pose.a)); + int32_t dz = 0; + + // if( finder->debug ) + // RecordRay( pose.x, + // pose.y, + // pose.x + range.max * cos(pose.a), + // pose.y + range.max * sin(pose.a) ); + + // fast integer line 3d algorithm adapted from Cohen's code from + // Graphics Gems IV + int n, sx, sy, sz, exy, exz, ezy, ax, ay, az, bx, by, bz; + sx = sgn(dx); sy = sgn(dy); sz = sgn(dz); + ax = abs(dx); ay = abs(dy); az = abs(dz); + bx = 2*ax; by = 2*ay; bz = 2*az; + exy = ay-ax; exz = az-ax; ezy = ay-az; + n = ax+ay+az; + + // printf( "Raytracing from (%d,%d,%d) steps (%d,%d,%d) %d\n", + // x,y,z, dx,dy,dz, n ); + + // superregion coords + stg_point_int_t lastsup; + lastsup.x = INT_MAX; // an unlikely first raytrace + lastsup.y = INT_MAX; + + stg_point_int_t lastreg = {0,0}; + lastsup.x = INT_MAX; // an unlikely first raytrace + lastsup.y = INT_MAX; + + SuperRegion* sr = NULL; + Region* r = NULL; + + //puts( "RAYTRACE" ); + + while ( n-- ) + { + // superregion coords + stg_point_int_t sup; + sup.x = x >> SRBITS; + sup.y = y >> SRBITS; + + // printf( "pixel [%d %d]\tS[ %d %d ]\t", + // x, y, sup.x, sup.y ); - // find the global integer bitmap address of the ray - int32_t x = (int32_t)(pose.x*ppm); - int32_t y = (int32_t)(pose.y*ppm); - int32_t z = 0; + if( ! (sup.x == lastsup.x && sup.y == lastsup.y )) + { + sr = (SuperRegion*)g_hash_table_lookup( superregions, (void*)&sup ); + lastsup = sup; // remember these coords + } - int32_t xstart = x; - int32_t ystart = y; + if( sr ) + { + // find the region coords inside this superregion + stg_point_int_t reg; + reg.x = (x - ( sup.x << SRBITS)) >> RBITS; + reg.y = (y - ( sup.y << SRBITS)) >> RBITS; - // and the x and y offsets of the ray - int32_t dx = (int32_t)(ppm*range * cos(pose.a)); - int32_t dy = (int32_t)(ppm*range * sin(pose.a)); - int32_t dz = 0; + // printf( "R[ %d %d ]\t", reg.x, reg.y ); - // if( finder->debug ) - // RecordRay( pose.x, - // pose.y, - // pose.x + range.max * cos(pose.a), - // pose.y + range.max * sin(pose.a) ); + if( ! (reg.x == lastreg.x && reg.y == lastreg.y )) + { + r = sr->GetRegion( reg.x, reg.y ); + lastreg = reg; + } - // fast integer line 3d algorithm adapted from Cohen's code from - // Graphics Gems IV - int n, sx, sy, sz, exy, exz, ezy, ax, ay, az, bx, by, bz; - sx = sgn(dx); sy = sgn(dy); sz = sgn(dz); - ax = abs(dx); ay = abs(dy); az = abs(dz); - bx = 2*ax; by = 2*ay; bz = 2*az; - exy = ay-ax; exz = az-ax; ezy = ay-az; - n = ax+ay+az; + if( r && r->count ) + { + // compute the pixel offset inside this region + stg_point_int_t cell; + cell.x = x - ((sup.x << SRBITS) + (reg.x << RBITS)); + cell.y = y - ((sup.y << SRBITS) + (reg.y << RBITS)); - // printf( "Raytracing from (%d,%d,%d) steps (%d,%d,%d) %d\n", - // x,y,z, dx,dy,dz, n ); + // printf( "C[ %d %d ]\t", cell.x, cell.y ); - // superregion coords - stg_point_int_t lastsup; - lastsup.x = INT_MAX; // an unlikely first raytrace - lastsup.y = INT_MAX; + for( GSList* list = r->GetCell( cell.x, cell.y )->list; + list; + list = list->next ) + { + StgBlock* block = (StgBlock*)list->data; + assert( block ); - stg_point_int_t lastreg = {0,0}; - lastsup.x = INT_MAX; // an unlikely first raytrace - lastsup.y = INT_MAX; - - SuperRegion* sr = NULL; - Region* r = NULL; - - //puts( "RAYTRACE" ); - - while ( n-- ) - { - // superregion coords - stg_point_int_t sup; - sup.x = x >> SRBITS; - sup.y = y >> SRBITS; - - // printf( "pixel [%d %d]\tS[ %d %d ]\t", - // x, y, sup.x, sup.y ); - - if( ! (sup.x == lastsup.x && sup.y == lastsup.y )) - { - sr = (SuperRegion*)g_hash_table_lookup( superregions, (void*)&sup ); - lastsup = sup; // remember these coords + // if this block does not belong to the searching model and it + // matches the predicate and it's in the right z range + if( //block && (block->Model() != finder) && + (ztest ? block->IntersectGlobalZ( pose.z ) : true) && + (*func)( block, mod, arg ) ) + { + // a hit! + sample->block = block; + sample->range = hypot( (x-xstart)/ppm, (y-ystart)/ppm ); + return; + } } + } + } - if( sr ) - { - // find the region coords inside this superregion - stg_point_int_t reg; - reg.x = (x - ( sup.x << SRBITS)) >> RBITS; - reg.y = (y - ( sup.y << SRBITS)) >> RBITS; + // printf( "\t step %d n %d pixel [ %d, %d ] block [ %d %d ] index [ %d %d ] \n", + // //coarse [ %d %d ]\n", + // count++, n, x, y, blockx, blocky, b_dx, b_dy ); - // printf( "R[ %d %d ]\t", reg.x, reg.y ); - - if( ! (reg.x == lastreg.x && reg.y == lastreg.y )) - { - r = sr->GetRegion( reg.x, reg.y ); - lastreg = reg; - } - - if( r && r->count ) - { - // compute the pixel offset inside this region - stg_point_int_t cell; - cell.x = x - ((sup.x << SRBITS) + (reg.x << RBITS)); - cell.y = y - ((sup.y << SRBITS) + (reg.y << RBITS)); - - // printf( "C[ %d %d ]\t", cell.x, cell.y ); - - for( GSList* list = r->GetCell( cell.x, cell.y )->list; - list; - list = list->next ) - { - StgBlock* block = (StgBlock*)list->data; - assert( block ); - - // if this block does not belong to the searching model and it - // matches the predicate and it's in the right z range - if( //block && (block->Model() != finder) && - (ztest ? block->IntersectGlobalZ( pose.z ) : true) && - (*func)( block, mod, arg ) ) - { - // a hit! - sample->block = block; - sample->range = hypot( (x-xstart)/ppm, (y-ystart)/ppm ); - return; - } - } - } - } - - // printf( "\t step %d n %d pixel [ %d, %d ] block [ %d %d ] index [ %d %d ] \n", - // //coarse [ %d %d ]\n", - // count++, n, x, y, blockx, blocky, b_dx, b_dy ); - - // increment our pixel in the correct direction - if ( exy < 0 ) { - if ( exz < 0 ) { - x += sx; exy += by; exz += bz; - } - else { - z += sz; exz -= bx; ezy += by; - } - } - else { - if ( ezy < 0 ) { - z += sz; - exz -= bx; ezy += by; - } - else { - y += sy; exy -= bx; ezy -= bz; - } - } - // puts(""); + // increment our pixel in the correct direction + if ( exy < 0 ) { + if ( exz < 0 ) { + x += sx; exy += by; exz += bz; } + else { + z += sz; exz -= bx; ezy += by; + } + } + else { + if ( ezy < 0 ) { + z += sz; + exz -= bx; ezy += by; + } + else { + y += sy; exy -= bx; ezy -= bz; + } + } + // puts(""); + } - // hit nothing - return; + // hit nothing + return; } static void _save_cb( gpointer key, gpointer data, gpointer user ) Modified: code/stage/trunk/libstage/worldfile.cc =================================================================== --- code/stage/trunk/libstage/worldfile.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/worldfile.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -1402,7 +1402,7 @@ } -bool Worldfile::PropertyExists( int section, char* token ) +bool Worldfile::PropertyExists( int section, const char* token ) { return( this->GetProperty( section, token ) ? true : false ); } Modified: code/stage/trunk/libstage/worldfile.hh =================================================================== --- code/stage/trunk/libstage/worldfile.hh 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/worldfile.hh 2008-07-04 22:58:26 UTC (rev 6765) @@ -268,7 +268,7 @@ // returns true iff the property exists in the file, so that you can // be sure that GetProperty() will work - bool PropertyExists( int section, char* token ); + bool PropertyExists( int section, const char* token ); // Set the value of an property. private: void SetPropertyValue( CProperty* property, int index, const char *value); Modified: code/stage/trunk/libstage/worldgui.cc =================================================================== --- code/stage/trunk/libstage/worldgui.cc 2008-07-04 22:10:13 UTC (rev 6764) +++ code/stage/trunk/libstage/worldgui.cc 2008-07-04 22:58:26 UTC (rev 6765) @@ -115,20 +115,25 @@ #endif StgWorldGui::StgWorldGui(int W,int H,const char* L) : - Fl_Window(W,H,L) + Fl_Window(W,H,L ) { //size_range( 100,100 ); // set minimum window size oDlg = NULL; graphics = true; paused = false; + // improve the title bar to say "Stage: <worldfile name>" + std::string title = "Stage: "; + title += L; + label( title.c_str() ); + 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 = new Fl_Menu_Bar(0,0, W, 30); mbar->textsize(12); canvas = new StgCanvas( this,0,30,W,H-30 ); @@ -166,6 +171,7 @@ delete canvas; } + void StgWorldGui::Load( const char* filename ) { PRINT_DEBUG1( "%s.Load()", token ); This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. ------------------------------------------------------------------------- Sponsored by: SourceForge.net Community Choice Awards: VOTE NOW! Studies have shown that voting for your favorite open source project, along with a healthy diet, reduces your potential for chronic lameness and boredom. Vote Now at http://www.sourceforge.net/community/cca08 _______________________________________________ Playerstage-commit mailing list Playerstage-commit@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/playerstage-commit