canvas.cc
Go to the documentation of this file.
00001 
00013 #include "stage.hh"
00014 #include "canvas.hh"
00015 #include "worldfile.hh"
00016 #include "texture_manager.hh"
00017 #include "replace.h"
00018 
00019 #include <string>
00020 #include <sstream>
00021 #include <png.h>
00022 #include <algorithm>
00023 #include <functional>      // For greater<int>( )
00024 
00025 #include "region.hh"
00026 #include "file_manager.hh"
00027 #include "options_dlg.hh"
00028 
00029 using namespace Stg;
00030 
00031 static  const int checkImageWidth = 2;
00032 static  const int       checkImageHeight = 2;
00033 static  GLubyte checkImage[checkImageHeight][checkImageWidth][4];
00034 static bool blur = true;
00035 
00036 static bool init_done = false;
00037 static bool texture_load_done = false;
00038 
00039 //GLuint glowTex;
00040 GLuint checkTex;
00041 
00042 void Canvas::TimerCallback( Canvas* c )
00043 {
00044   if( c->world->dirty )
00045     {
00046       //puts( "timer redraw" );
00047       c->redraw();
00048       c->world->dirty = false;
00049     }
00050   
00051   Fl::repeat_timeout( c->interval/1000.0,
00052                       (Fl_Timeout_Handler)Canvas::TimerCallback, 
00053                       c);
00054 }
00055 
00056 Canvas::Canvas( WorldGui* world, 
00057                 int x, int y, 
00058                 int width, int height) :
00059   Fl_Gl_Window( x, y, width, height ),
00060   colorstack(),  
00061   models_sorted(),
00062   current_camera( NULL ),
00063   camera(),
00064   perspective_camera(),
00065   dirty_buffer( false ),  
00066   wf( NULL ),
00067   startx( -1 ),
00068   starty( -1 ),
00069   selected_models(),
00070   last_selection( NULL ),
00071   interval( 40 ), // msec between redraws
00072   // initialize Option objects
00073   //  showBlinken( "Blinkenlights", "show_blinkenlights", "", true, world ), 
00074   showBBoxes( "Debug/Bounding boxes", "show_boundingboxes", "^b", false, world ),
00075   showBlocks( "Blocks", "show_blocks", "b", true, world ),
00076   showBlur( "Trails/Blur", "show_trailblur", "^d", false, world ),
00077   showClock( "Clock", "show_clock", "c", true, world ),
00078   showData( "Data", "show_data", "d", false, world ),
00079   showFlags( "Flags", "show_flags", "l",  true, world ),
00080   showFollow( "Follow", "show_follow", "f", false, world ),
00081   showFootprints( "Footprints", "show_footprints", "o", false, world ),
00082   showGrid( "Grid", "show_grid", "g", true, world ),
00083   showOccupancy( "Debug/Occupancy", "show_occupancy", "^o", false, world ),
00084   showScreenshots( "Save screenshots", "screenshots", "", false, world ),
00085   showStatus( "Status", "show_status", "s", true, world ),
00086   showTrailArrows( "Trails/Rising Arrows", "show_trailarrows", "^a", false, world ),
00087   showTrailRise( "Trails/Rising blocks", "show_trailrise", "^r", false, world ),
00088   showTrails( "Trails/Fast", "show_trailfast", "^f", false, world ),
00089   showVoxels( "Debug/Voxels", "show_voxels", "^v", false, world ),
00090   pCamOn( "Perspective camera", "pcam_on", "r", false, world ),
00091   visualizeAll( "Selected only", "vis_all", "v", false, world ),
00092   // and the rest 
00093   graphics( true ),
00094   world( world ),
00095   frames_rendered_count( 0 ),
00096   screenshot_frame_skip( 1 )
00097 {
00098   end();  
00099   //show(); // must do this so that the GL context is created before configuring GL
00100   // but that line causes a segfault in Linux/X11! TODO: test in OS X
00101   
00102   perspective_camera.setPose( 0.0, -4.0, 3.0 );
00103   current_camera = &camera;
00104   setDirtyBuffer();
00105         
00106   // enable accumulation buffer
00107   //mode( mode() | FL_ACCUM );
00108   //assert( can_do( FL_ACCUM ) );
00109 }
00110 
00111 void Canvas::InitGl()
00112 {
00113   valid(1);
00114   FixViewport(w(), h());
00115   
00116   // set gl state that won't change every redraw
00117   glClearColor ( 0.7, 0.7, 0.8, 1.0);
00118   glDisable( GL_LIGHTING );
00119   glEnable( GL_DEPTH_TEST );
00120   glDepthFunc( GL_LESS );
00121   // culling disables text drawing on OS X, so I've disabled it until I understand why
00122   //glCullFace( GL_BACK );
00123   //glEnable (GL_CULL_FACE);
00124   glEnable( GL_BLEND );
00125   glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA );
00126   glEnable( GL_LINE_SMOOTH );
00127   glHint( GL_LINE_SMOOTH_HINT, GL_FASTEST );
00128   glDepthMask( GL_TRUE );
00129   glEnable( GL_TEXTURE_2D );
00130   glEnableClientState( GL_VERTEX_ARRAY );
00131   glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
00132   
00133   // install a font
00134   gl_font( FL_HELVETICA, 12 );  
00135 
00136   blur = false;
00137   
00138   glTexEnvf(GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_MODULATE);
00139     
00140   init_done = true; 
00141 }
00142 
00143 
00144 void Canvas::InitTextures()
00145 {
00146   // load textures
00147   std::string fullpath = FileManager::findFile( "assets/stall.png" );
00148   if ( fullpath == "" ) 
00149     {
00150       PRINT_DEBUG( "Unable to load stall texture.\n" );
00151     }
00152  
00153   //printf( "stall icon %s\n", fullpath.c_str() );
00154  
00155   GLuint stall_id = TextureManager::getInstance().loadTexture( fullpath.c_str() );
00156   TextureManager::getInstance()._stall_texture_id = stall_id;
00157 
00158   fullpath = FileManager::findFile( "assets/mainspower.png" );
00159   if ( fullpath == "" ) 
00160     {
00161       PRINT_DEBUG( "Unable to load mains texture.\n" );
00162     }
00163   
00164   //    printf( "mains icon %s\n", fullpath.c_str() );
00165 
00166   GLuint mains_id = TextureManager::getInstance().loadTexture( fullpath.c_str() );
00167   TextureManager::getInstance()._mains_texture_id = mains_id;
00168   
00169   //   // generate a small glow texture
00170   //   GLubyte* pixels = new GLubyte[ 4 * 128 * 128 ];
00171 
00172   //   for( int x=0; x<128; x++ )
00173   //     for( int y=0; y<128; y++ )
00174   //            {                 
00175   //              GLubyte* p = &pixels[ 4 * (128*y + x)];
00176   //              p[0] = (GLubyte)255; // red
00177   //              p[1] = (GLubyte)0; // green
00178   //              p[2] = (GLubyte)0; // blue
00179   //              p[3] = (GLubyte)128; // alpha
00180   //            }
00181 
00182 
00183   //   glGenTextures(1, &glowTex );
00184   //   glBindTexture( GL_TEXTURE_2D, glowTex );
00185   
00186   //   glTexImage2D( GL_TEXTURE_2D, 0, GL_RGBA, 128, 128, 0, 
00187   //                                     GL_RGBA, GL_UNSIGNED_BYTE, pixels );
00188 
00189   //   delete[] pixels;
00190 
00191   // draw a check into a bitmap, then load that into a texture
00192   int i, j;
00193   for (i = 0; i < checkImageHeight; i++) 
00194     for (j = 0; j < checkImageWidth; j++) 
00195       {                 
00196         int even = (i+j)%2;
00197         checkImage[i][j][0] = (GLubyte) 255 - 10*even;
00198         checkImage[i][j][1] = (GLubyte) 255 - 10*even;
00199         checkImage[i][j][2] = (GLubyte) 255;// - 5*even;
00200         checkImage[i][j][3] = 255;
00201       }
00202   
00203   glGenTextures(1, &checkTex );          
00204   glBindTexture(GL_TEXTURE_2D, checkTex);
00205   
00206   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT);
00207   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT);
00208   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
00209   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
00210   
00211   glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, checkImageWidth, checkImageHeight, 
00212                0, GL_RGBA, GL_UNSIGNED_BYTE, checkImage);
00213 
00214   texture_load_done = true;
00215 }
00216 
00217 
00218 Canvas::~Canvas()
00219 { 
00220   // nothing to do
00221 }
00222 
00223 Model* Canvas::getModel( int x, int y )
00224 {
00225   // render all models in a unique color
00226   make_current(); // make sure the GL context is current
00227   glClearColor( 1,1,1,1 ); // white
00228   glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
00229   glLoadIdentity();
00230   current_camera->SetProjection();
00231   current_camera->Draw();
00232 
00233   glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
00234   glDisable(GL_DITHER);
00235   glDisable(GL_BLEND); // turns off alpha blending, so we read back
00236   // exactly what we write to a pixel
00237 
00238   // render all top-level, draggable models in a color that is their
00239   // id 
00240   FOR_EACH( it, world->World::children )
00241     {
00242       Model* mod = (*it);
00243                 
00244       if( mod->gui.move )
00245         {
00246           uint8_t rByte, gByte, bByte, aByte;
00247           uint32_t modelId = mod->id;
00248           rByte = modelId;
00249           gByte = modelId >> 8;
00250           bByte = modelId >> 16;
00251           aByte = modelId >> 24;
00252 
00253           //printf("mod->Id(): 0x%X, rByte: 0x%X, gByte: 0x%X, bByte: 0x%X, aByte: 0x%X\n", modelId, rByte, gByte, bByte, aByte);
00254                         
00255           glColor4ub( rByte, gByte, bByte, aByte );
00256           mod->DrawPicker();
00257         }
00258     }
00259         
00260   glFlush(); // make sure the drawing is done
00261 
00262   // read the color of the pixel in the back buffer under the mouse
00263   // pointer
00264   GLint viewport[4];
00265   glGetIntegerv(GL_VIEWPORT,viewport);
00266 
00267   uint8_t rgbaByte[4];
00268   uint32_t modelId;
00269         
00270   glReadPixels( x,viewport[3]-y,1,1,
00271                 GL_RGBA,GL_UNSIGNED_BYTE,&rgbaByte[0] );
00272         
00273   modelId = rgbaByte[0];
00274   modelId |= rgbaByte[1] << 8;
00275   modelId |= rgbaByte[2] << 16;
00276   //modelId |= rgbaByte[3] << 24;
00277         
00278   //    printf("Clicked rByte: 0x%X, gByte: 0x%X, bByte: 0x%X, aByte: 0x%X\n", rgbaByte[0], rgbaByte[1], rgbaByte[2], rgbaByte[3]);
00279   //    printf("-->model Id = 0x%X\n", modelId);
00280         
00281   Model* mod = Model::LookupId( modelId );
00282 
00283   //printf("%p %s %d %x\n", mod, mod ? mod->Token() : "(none)", modelId, modelId );
00284 
00285   // put things back the way we found them
00286   glEnable(GL_DITHER);
00287   glEnable(GL_BLEND);
00288   glClearColor ( 0.7, 0.7, 0.8, 1.0);
00289   
00290   // useful for debugging the picker
00291   //Screenshot();
00292         
00293   return mod;
00294 }
00295 
00296 bool Canvas::selected( Model* mod ) 
00297 {
00298   return( std::find( selected_models.begin(), selected_models.end(), mod ) != selected_models.end() );
00299 }
00300 
00301 void Canvas::select( Model* mod ) {
00302   if( mod )
00303     {
00304       last_selection = mod;
00305       selected_models.push_front( mod );
00306                 
00307       //                mod->Disable();
00308       redraw();
00309     }
00310 }
00311 
00312 void Canvas::unSelect( Model* mod ) 
00313 {
00314   if( mod )
00315     {
00316       EraseAll( mod, selected_models );
00317       redraw();
00318     }
00319 }
00320 
00321 void Canvas::unSelectAll() 
00322 { 
00323   selected_models.clear();
00324 }
00325 
00326 // convert from 2d window pixel to 3d world coordinates
00327 void Canvas::CanvasToWorld( int px, int py, 
00328                             double *wx, double *wy, double* wz )
00329 {
00330   if( px <= 0 )
00331     px = 1;
00332   else if( px >= w() )
00333     px = w() - 1;
00334   if( py <= 0 )
00335     py = 1;
00336   else if( py >= h() )
00337     py = h() - 1;
00338         
00339   //redraw the screen only if the camera model isn't active.
00340   //TODO new selection technique will simply use drawfloor to result in z = 0 always and prevent strange behaviours near walls
00341   //TODO refactor, so glReadPixels reads (then caches) the whole screen only when the camera changes.
00342   if( true || dirtyBuffer() ) {
00343     glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
00344     current_camera->SetProjection();
00345     current_camera->Draw();
00346     DrawFloor(); //call this rather than renderFrame for speed - this won't give correct z values
00347     dirty_buffer = false;
00348   }
00349         
00350   int viewport[4];
00351   glGetIntegerv(GL_VIEWPORT, viewport);
00352 
00353   GLdouble modelview[16];
00354   glGetDoublev(GL_MODELVIEW_MATRIX, modelview);
00355 
00356   GLdouble projection[16];      
00357   glGetDoublev(GL_PROJECTION_MATRIX, projection);
00358 
00359   GLfloat pz;
00360   glReadPixels( px, h()-py, 1, 1, GL_DEPTH_COMPONENT, GL_FLOAT, &pz );
00361   gluUnProject( px, w()-py, pz, modelview, projection, viewport, wx,wy,wz );    
00362 }
00363 
00364 int Canvas::handle(int event) 
00365 {
00366   //printf( "cam %.2f %.2f\n", camera.yaw(), camera.pitch() );
00367 
00368   switch(event) 
00369     {
00370     case FL_MOUSEWHEEL:
00371       if( pCamOn == true ) {
00372         perspective_camera.scroll( Fl::event_dy() / 10.0 );
00373       }
00374       else {
00375         camera.scale( Fl::event_dy(),  Fl::event_x(), w(), Fl::event_y(), h() );
00376       }
00377       invalidate();
00378       redraw();
00379       return 1;
00380                 
00381     case FL_MOVE: // moused moved while no button was pressed
00382       if( Fl::event_state( FL_META ) )
00383         {
00384           puts( "TODO: HANDLE HISTORY" );
00385           //world->paused = ! world->paused;
00386           return 1;
00387         }
00388                 
00389       if ( startx >=0 ) 
00390         {
00391           // mouse pointing to valid value
00392                          
00393           if( Fl::event_state( FL_CTRL ) ) // rotate the camera view
00394             {
00395               int dx = Fl::event_x() - startx;
00396               int dy = Fl::event_y() - starty;
00397                                   
00398               if( pCamOn == true ) {
00399                 perspective_camera.addYaw( -dx );
00400                 perspective_camera.addPitch( -dy );
00401               } 
00402               else {
00403                 camera.addPitch( - 0.5 * static_cast<double>( dy ) );
00404                 camera.addYaw( - 0.5 * static_cast<double>( dx ) );
00405               }
00406               invalidate();
00407               redraw();
00408             }
00409           else if( Fl::event_state( FL_ALT ) )
00410             {   
00411               int dx = Fl::event_x() - startx;
00412               int dy = Fl::event_y() - starty;
00413                                   
00414               if( pCamOn == true ) {
00415                 perspective_camera.move( -dx, dy, 0.0 );
00416               } 
00417               else {
00418                 camera.move( -dx, dy );
00419               }
00420               invalidate();
00421             }
00422         }
00423       startx = Fl::event_x();
00424       starty = Fl::event_y();
00425       return 1;
00426     case FL_PUSH: // button pressed
00427       {
00428         //else
00429         {
00430           Model* mod = getModel( startx, starty );
00431           startx = Fl::event_x();
00432           starty = Fl::event_y();
00433           selectedModel = false;
00434           switch( Fl::event_button() )
00435             {
00436             case 1:
00437               clicked_empty_space = ( mod == NULL );
00438               empty_space_startx = startx;
00439               empty_space_starty = starty;
00440               if( mod ) { 
00441                 // clicked a model
00442                 if ( Fl::event_state( FL_SHIFT ) ) {
00443                   // holding shift, toggle selection
00444                   if ( selected( mod ) ) 
00445                     unSelect( mod );
00446                   else {
00447                     select( mod );
00448                     selectedModel = true; // selected a model
00449                   }
00450                 }
00451                 else {
00452                   if ( !selected( mod ) ) {
00453                     // clicked on an unselected model while
00454                     //  not holding shift, this is the new
00455                     //  selection
00456                     unSelectAll();
00457                     select( mod );
00458                   }
00459                   selectedModel = true; // selected a model
00460                 }
00461               }
00462                                   
00463               redraw(); // probably required                                     
00464               return 1;
00465             case 3:
00466               {
00467                 // leave selections alone
00468                 // rotating handled within FL_DRAG
00469                 return 1;
00470               }
00471             default:
00472               return 0;
00473             }    
00474         }
00475       }
00476           
00477     case FL_DRAG: // mouse moved while button was pressed
00478       {
00479         int dx = Fl::event_x() - startx;
00480         int dy = Fl::event_y() - starty;
00481 
00482         if ( Fl::event_state( FL_BUTTON1 ) && Fl::event_state( FL_CTRL ) == false ) {
00483           // Left mouse button drag
00484           if ( selectedModel ) {
00485             // started dragging on a selected model
00486                                 
00487             double sx,sy,sz;
00488             CanvasToWorld( startx, starty,
00489                            &sx, &sy, &sz );
00490             double x,y,z;
00491             CanvasToWorld( Fl::event_x(), Fl::event_y(),
00492                            &x, &y, &z );
00493             // move all selected models to the mouse pointer
00494             FOR_EACH( it, selected_models )
00495               {
00496                 Model* mod = *it;
00497                 mod->AddToPose( x-sx, y-sy, 0, 0 );
00498               }
00499           }
00500           else {
00501             // started dragging on empty space or an
00502             //  unselected model, move the canvas
00503             if( pCamOn == true ) {
00504               perspective_camera.move( -dx, dy, 0.0 );
00505             } 
00506             else {
00507               camera.move( -dx, dy );
00508             }
00509             invalidate(); // so the projection gets updated
00510           }
00511         }
00512         else if ( Fl::event_state( FL_BUTTON3 ) || ( Fl::event_state( FL_BUTTON1 ) &&  Fl::event_state( FL_CTRL )  ) ) {
00513           // rotate all selected models
00514 
00515           if( selected_models.size() )
00516             {
00517               FOR_EACH( it, selected_models )
00518                 {
00519                   Model* mod = *it;
00520                   mod->AddToPose( 0,0,0, 0.05*(dx+dy) );
00521                 }
00522             }
00523             else
00524               {
00525                 //printf( "button 2\n" );
00526                 
00527                 int dx = Fl::event_x() - startx;
00528                 int dy = Fl::event_y() - starty;
00529                 
00530                 if( pCamOn == true ) {
00531                   perspective_camera.addYaw( -dx );
00532                   perspective_camera.addPitch( -dy );
00533                 } 
00534                 else {
00535                   camera.addPitch( - 0.5 * static_cast<double>( dy ) );
00536                   camera.addYaw( - 0.5 * static_cast<double>( dx ) );
00537                 }
00538               }
00539             invalidate();
00540             redraw();
00541             }             
00542           
00543           startx = Fl::event_x();
00544           starty = Fl::event_y();
00545           
00546           redraw();
00547           return 1;
00548         } // end case FL_DRAG
00549         
00550     case FL_RELEASE:   // mouse button released
00551       if( empty_space_startx == Fl::event_x() && empty_space_starty == Fl::event_y() && clicked_empty_space == true ) {
00552         // clicked on empty space, unselect all
00553         unSelectAll();
00554         redraw();
00555       }
00556       return 1;
00557 
00558     case FL_FOCUS:
00559     case FL_UNFOCUS:
00560       //.... Return 1 if you want keyboard events, 0 otherwise
00561       return 1;
00562 
00563     case FL_KEYBOARD:
00564       switch( Fl::event_key() )
00565         {
00566         case FL_Left:
00567           if( pCamOn == false ) { camera.move( -10, 0 ); } 
00568           else { perspective_camera.strafe( -0.5 ); } break;
00569         case FL_Right: 
00570           if( pCamOn == false ) {camera.move( 10, 0 ); } 
00571           else { perspective_camera.strafe( 0.5 ); } break;
00572         case FL_Down:  
00573           if( pCamOn == false ) {camera.move( 0, -10 ); } 
00574           else { perspective_camera.forward( -0.5 ); } break;
00575         case FL_Up:  
00576           if( pCamOn == false ) {camera.move( 0, 10 ); } 
00577           else { perspective_camera.forward( 0.5 ); } break;
00578         default:
00579           redraw(); // we probably set a display config - so need this
00580           return 0; // keypress unhandled
00581         }
00582                 
00583       invalidate(); // update projection
00584       return 1;
00585                         
00586       //        case FL_SHORTCUT:
00587       //                //... shortcut, key is in Fl::event_key(), ascii in Fl::event_text()
00588       //                //... Return 1 if you understand/use the shortcut event, 0 otherwise...
00589       //                return 1;
00590     default:
00591       // pass other events to the base class...
00592       //printf( "EVENT %d\n", event );
00593       return Fl_Gl_Window::handle(event);
00594                         
00595     } // end switch( event )
00596 
00597   return 0;
00598 }
00599 
00600 void Canvas::FixViewport(int W,int H) 
00601 {
00602   glLoadIdentity();
00603   glViewport(0,0,W,H);
00604 }
00605 
00606 void Canvas::AddModel( Model*  mod  )
00607 {
00608   models_sorted.push_back( mod );
00609   redraw();
00610 }
00611 
00612 void Canvas::RemoveModel( Model*  mod  )
00613 {
00614   printf( "removing model %s from canvas list\n", mod->Token() );
00615   EraseAll( mod, models_sorted );
00616 }
00617 
00618 void Canvas::DrawGlobalGrid()
00619 {
00620   bounds3d_t bounds = world->GetExtent();
00621 
00622   glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
00623 
00624   glEnable(GL_POLYGON_OFFSET_FILL);
00625   glPolygonOffset(2.0, 2.0);
00626   glDisable(GL_BLEND);
00627 
00628   glEnable(GL_TEXTURE_2D);
00629   glBindTexture(GL_TEXTURE_2D, checkTex );
00630   glColor3f( 1.0, 1.0, 1.0 );
00631 
00632   glBegin(GL_QUADS);
00633   glTexCoord2f( bounds.x.min/2.0, bounds.y.min/2.0 ); 
00634   glVertex2f( bounds.x.min, bounds.y.min );
00635   glTexCoord2f( bounds.x.max/2.0, bounds.y.min/2.0); 
00636   glVertex2f(  bounds.x.max, bounds.y.min );
00637   glTexCoord2f( bounds.x.max/2.0, bounds.y.max/2.0 ); 
00638   glVertex2f(  bounds.x.max, bounds.y.max );
00639   glTexCoord2f( bounds.x.min/2.0, bounds.y.max/2.0 ); 
00640   glVertex2f( bounds.x.min, bounds.y.max );
00641   glEnd();
00642 
00643   glDisable(GL_TEXTURE_2D);
00644   glEnable(GL_BLEND);
00645   
00646   glDisable(GL_POLYGON_OFFSET_FILL );
00647 
00648 
00649   /*   printf( "bounds [%.2f %.2f] [%.2f %.2f] [%.2f %.2f]\n",
00650        bounds.x.min, bounds.x.max,
00651        bounds.y.min, bounds.y.max,
00652        bounds.z.min, bounds.z.max );
00653                          
00654   */
00655   
00656   /* simple scaling of axis labels - could be better */
00657   int skip = (int)( 50 / camera.scale());
00658   if( skip < 1 ) skip = 1;
00659   if( skip > 2 && skip % 2 ) skip += 1;
00660 
00661   //printf( "scale %.4f\n", camera.scale() );
00662 
00663   char str[64]; 
00664   PushColor( 0.2, 0.2, 0.2, 1.0 ); // pale gray
00665 
00666   for( double i=0; i < bounds.x.max; i+=skip)
00667     {      
00668       snprintf( str, 16, "%d", (int)i );
00669       Gl::draw_string(  i, 0, 0, str );
00670     }
00671 
00672   for( double i=0; i >= bounds.x.min; i-=skip)
00673     {
00674       snprintf( str, 16, "%d", (int)i );
00675       Gl::draw_string(  i, 0, 0, str );
00676     }
00677 
00678   
00679   for( double i=0; i < bounds.y.max; i+=skip)
00680     {
00681       snprintf( str, 16, "%d", (int)i );
00682       Gl::draw_string(  0, i, 0, str );
00683     }
00684 
00685   for( double i=0; i >= bounds.y.min; i-=skip)
00686     {
00687       snprintf( str, 16, "%d", (int)i );
00688       Gl::draw_string(  0, i, 0, str );
00689     }
00690 
00691 
00692   PopColor();
00693   
00694 }
00695 
00696 //draw the floor without any grid ( for robot's perspective camera model )
00697 void Canvas::DrawFloor()
00698 {
00699   bounds3d_t bounds = world->GetExtent();
00700         
00701   glEnable(GL_POLYGON_OFFSET_FILL);
00702   glPolygonOffset(2.0, 2.0);
00703         
00704   glColor4f( 1.0, 1.0, 1.0, 1.0 );
00705 
00706   glBegin(GL_QUADS);
00707   glVertex2f( bounds.x.min, bounds.y.min );
00708   glVertex2f( bounds.x.max, bounds.y.min );
00709   glVertex2f( bounds.x.max, bounds.y.max );
00710   glVertex2f( bounds.x.min, bounds.y.max );
00711   glEnd();
00712 }
00713 
00714 void Canvas::DrawBlocks() 
00715 {
00716   FOR_EACH( it, models_sorted )
00717     (*it)->DrawBlocksTree();
00718 }
00719 
00720 void Canvas::DrawBoundingBoxes() 
00721 {
00722   glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
00723   glLineWidth( 2.0 );
00724   glPointSize( 5.0 );
00725   glDisable (GL_CULL_FACE);
00726   
00727   world->DrawBoundingBoxTree();
00728   
00729   glEnable (GL_CULL_FACE);
00730   glLineWidth( 1.0 );
00731   glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
00732 }
00733 
00734 void Canvas::resetCamera()
00735 {
00736   float max_x = 0, max_y = 0, min_x = 0, min_y = 0;
00737         
00738   //TODO take orrientation ( `a' ) and geom.pose offset into consideration
00739   FOR_EACH( it, world->World::children )
00740     {    
00741       Model* ptr = (*it);
00742       Pose pose = ptr->GetPose();
00743       Geom geom = ptr->GetGeom();
00744                 
00745       float tmp_min_x = pose.x - geom.size.x / 2.0;
00746       float tmp_max_x = pose.x + geom.size.x / 2.0;
00747       float tmp_min_y = pose.y - geom.size.y / 2.0;
00748       float tmp_max_y = pose.y + geom.size.y / 2.0;
00749                 
00750       if( tmp_min_x < min_x ) min_x = tmp_min_x;
00751       if( tmp_max_x > max_x ) max_x = tmp_max_x;
00752       if( tmp_min_y < min_y ) min_y = tmp_min_y;
00753       if( tmp_max_y > max_y ) max_y = tmp_max_y;
00754     }
00755         
00756   //do a complete reset
00757   float x = ( min_x + max_x ) / 2.0;
00758   float y = ( min_y + max_y ) / 2.0;
00759   camera.setPose( x, y );
00760   float scale_x = w() / (max_x - min_x) * 0.9;
00761   float scale_y = h() / (max_y - min_y) * 0.9;
00762   camera.setScale( scale_x < scale_y ? scale_x : scale_y );
00763         
00764   //TODO reset perspective cam
00765 }
00766 
00767 
00768 class DistFuncObj
00769 {
00770   meters_t x, y;
00771   DistFuncObj( meters_t x, meters_t y ) 
00772     : x(x), y(y) {}
00773   
00774   bool operator()(const Model* a, const Model* b ) const
00775   { 
00776     const Pose a_pose = a->GetGlobalPose();
00777     const Pose b_pose = b->GetGlobalPose();
00778          
00779     const meters_t a_dist = hypot( y - a_pose.y, x - a_pose.x );         
00780     const meters_t b_dist = hypot( y - b_pose.y, x - b_pose.x );
00781          
00782     return (  a_dist < b_dist );
00783   }
00784 };
00785 
00786 
00787 void Canvas::renderFrame()
00788 {
00789   //before drawing, order all models based on distance from camera
00790   //float x = current_camera->x();
00791   //float y = current_camera->y();
00792   //float sphi = -dtor( current_camera->yaw() );
00793         
00794   //estimate point of camera location - hard to do with orthogonal mode
00795   // x += -sin( sphi ) * 100;
00796   //y += -cos( sphi ) * 100;
00797         
00798   //double coords[2];
00799   //coords[0] = x;
00800   //coords[1] = y;
00801   
00802   // sort the list of models by inverse distance from the camera -
00803   // probably doesn't change too much between frames so this is
00804   // usually fast
00805   // TODO
00806   //models_sorted = g_list_sort_with_data( models_sorted, (GCompareDataFunc)compare_distance, coords );
00807   
00808   // TODO: understand why this doesn't work and fix it - cosmetic but important!
00809   //std::sort( models_sorted.begin(), models_sorted.end(), DistFuncObj(x,y) );
00810 
00811   glEnable( GL_DEPTH_TEST );
00812 
00813   if( ! showTrails )
00814     glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
00815   
00816   if( showOccupancy )
00817     ((WorldGui*)world)->DrawOccupancy();
00818   
00819   if( showVoxels )
00820     ((WorldGui*)world)->DrawVoxels();
00821   
00822   
00823   if( ! world->rt_cells.empty() )
00824     {
00825       glPushMatrix();                   
00826       GLfloat scale = 1.0/world->Resolution();
00827       glScalef( scale, scale, 1.0 ); // XX TODO - this seems slightly
00828                         
00829       world->PushColor( Color( 0,0,1,0.5) );
00830                         
00831       glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
00832                         
00833       glPointSize( 2 );
00834       glBegin( GL_POINTS );
00835                         
00836       for( unsigned int i=0;
00837            i < world->rt_cells.size();
00838            i++ )
00839         {
00840           char str[128];
00841           snprintf( str, 128, "(%d,%d)", 
00842                     world->rt_cells[i].x, 
00843                     world->rt_cells[i].y );
00844                                         
00845           Gl::draw_string(  world->rt_cells[i].x+1, 
00846                             world->rt_cells[i].y+1, 0.1, str );
00847                                         
00848           //printf( "x: %d y: %d\n", world->rt_regions[i].x, world->rt_regions[i].y );
00849           //glRectf( world->rt_cells[i].x+0.3, world->rt_cells[i].y+0.3,
00850           //     world->rt_cells[i].x+0.7, world->rt_cells[i].y+0.7 );
00851                                         
00852           glVertex2f( world->rt_cells[i].x, world->rt_cells[i].y );
00853                                         
00854         }
00855                         
00856       glEnd();
00857                         
00858 #if 1
00859       world->PushColor( Color( 0,1,0,0.2) );
00860       glBegin( GL_LINE_STRIP );
00861       for( unsigned int i=0;
00862            i < world->rt_cells.size();
00863            i++ )
00864         {                        
00865           glVertex2f( world->rt_cells[i].x+0.5, world->rt_cells[i].y+0.5 );
00866         }
00867       glEnd();
00868       world->PopColor();
00869 #endif
00870                         
00871       glPopMatrix();
00872       world->PopColor();
00873     }
00874         
00875   if( ! world->rt_candidate_cells.empty() )
00876     {
00877       glPushMatrix();                   
00878       GLfloat scale = 1.0/world->Resolution();
00879       glScalef( scale, scale, 1.0 ); // XX TODO - this seems slightly
00880                         
00881       world->PushColor( Color( 1,0,0,0.5) );
00882                         
00883       glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
00884                         
00885       for( unsigned int i=0;
00886            i < world->rt_candidate_cells.size();
00887            i++ )
00888         {
00889           //                     char str[128];
00890           //                     snprintf( str, 128, "(%d,%d)", 
00891           //                                              world->rt_candidate_cells[i].x, 
00892           //                                              world->rt_candidate_cells[i].y );
00893                                         
00894           //                     Gl::draw_string(  world->rt_candidate_cells[i].x+1, 
00895           //                                                                     world->rt_candidate_cells[i].y+1, 0.1, str );
00896                                         
00897           //printf( "x: %d y: %d\n", world->rt_regions[i].x, world->rt_regions[i].y );
00898           glRectf( world->rt_candidate_cells[i].x, world->rt_candidate_cells[i].y,
00899                    world->rt_candidate_cells[i].x+1, world->rt_candidate_cells[i].y+1 );
00900         }
00901                         
00902       world->PushColor( Color( 0,1,0,0.2) );
00903       glBegin( GL_LINE_STRIP );
00904       for( unsigned int i=0;
00905            i < world->rt_candidate_cells.size();
00906            i++ )
00907         {                        
00908           glVertex2f( world->rt_candidate_cells[i].x+0.5, world->rt_candidate_cells[i].y+0.5 );
00909         }
00910       glEnd();
00911       world->PopColor();
00912                         
00913       glPopMatrix();
00914       world->PopColor();
00915                         
00916       //world->rt_cells.clear();
00917     }
00918         
00919   if( showGrid )
00920     DrawGlobalGrid();
00921   else
00922     DrawFloor();
00923   
00924   if( showFootprints )
00925     {
00926       glDisable( GL_DEPTH_TEST ); // using alpha blending               
00927                 
00928       FOR_EACH( it, models_sorted )
00929         (*it)->DrawTrailFootprint();
00930                 
00931       glEnable( GL_DEPTH_TEST );
00932     }
00933   
00934   if( showFlags ) 
00935     {
00936       glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
00937       glBegin( GL_TRIANGLES );
00938 
00939       FOR_EACH( it, models_sorted )
00940         (*it)->DrawFlagList();
00941 
00942       glEnd();
00943     }
00944 
00945   if( showTrailArrows )
00946     FOR_EACH( it, models_sorted )
00947       (*it)->DrawTrailArrows();  
00948   
00949   if( showTrailRise )
00950     FOR_EACH( it, models_sorted )
00951       (*it)->DrawTrailBlocks();  
00952     
00953   if( showBlocks )
00954     DrawBlocks();
00955         
00956   if( showBBoxes )
00957     DrawBoundingBoxes();
00958         
00959   // TODO - finish this properly
00960   //LISTMETHOD( models_sorted, Model*, DrawWaypoints );
00961 
00962   FOR_EACH( it, selected_models )
00963     (*it)->DrawSelected();
00964 
00965   // useful debug - puts a point at the origin of each model
00966   //for( GList* it = world->World::children; it; it=it->next ) 
00967   // ((Model*)it->data)->DrawOriginTree();
00968   
00969   // draw the model-specific visualizations
00970   if( world->sim_time > 0 )
00971     {
00972       if( showData ) {
00973         if ( ! visualizeAll ) {
00974           FOR_EACH( it, world->World::children )
00975             (*it)->DataVisualizeTree( current_camera );
00976         }
00977         else if ( selected_models.size() > 0 ) {
00978           FOR_EACH( it, selected_models )
00979             (*it)->DataVisualizeTree( current_camera );
00980         }
00981         else if ( last_selection ) {
00982           last_selection->DataVisualizeTree( current_camera );
00983         }
00984       }
00985     }
00986 
00987   if( showGrid ) 
00988     FOR_EACH( it, models_sorted )
00989       (*it)->DrawGrid();
00990                   
00991   if( showStatus ) 
00992     {
00993       glPushMatrix();
00994       //ensure two icons can't be in the exact same plane
00995       if( camera.pitch() == 0 && !pCamOn )
00996         glTranslatef( 0, 0, 0.1 );
00997                 
00998       FOR_EACH( it, models_sorted )
00999         (*it)->DrawStatusTree( &camera );
01000                 
01001       glPopMatrix();
01002     }
01003   
01004   if( world->ray_list.size() > 0 )
01005     {
01006       glDisable( GL_DEPTH_TEST );
01007       PushColor( 0,0,0,0.5 );
01008       FOR_EACH( it, world->ray_list )
01009         {
01010           float* pts = *it;
01011           glBegin( GL_LINES );
01012           glVertex2f( pts[0], pts[1] );
01013           glVertex2f( pts[2], pts[3] );
01014           glEnd();
01015         }  
01016       PopColor();
01017       glEnable( GL_DEPTH_TEST );
01018                  
01019       world->ClearRays();
01020     } 
01021         
01022   if( showClock )
01023     {           
01024       glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
01025                 
01026       //use orthogonal projeciton without any zoom
01027       glMatrixMode (GL_PROJECTION);
01028       glPushMatrix(); //save old projection
01029       glLoadIdentity ();
01030       glOrtho( 0, w(), 0, h(), -100, 100 );     
01031       glMatrixMode (GL_MODELVIEW);
01032 
01033       glPushMatrix();
01034       glLoadIdentity();
01035       glDisable( GL_DEPTH_TEST );
01036 
01037       std::string clockstr = world->ClockString();
01038       if( showFollow == true && last_selection )
01039         clockstr.append( " [FOLLOW MODE]" );
01040                 
01041       float txtWidth = gl_width( clockstr.c_str());
01042       if( txtWidth < 200 ) txtWidth = 200;
01043       int txtHeight = gl_height();
01044                 
01045       const int margin = 5;
01046       int width, height;                
01047       width = txtWidth + 2 * margin;
01048       height = txtHeight + 2 * margin; 
01049                 
01050       // TIME BOX
01051       colorstack.Push( 0.8,0.8,1.0 ); // pale blue
01052       glRectf( 0, 0, width, height );
01053       colorstack.Push( 0,0,0 ); // black
01054       Gl::draw_string( margin, margin, 0, clockstr.c_str() );
01055       colorstack.Pop();
01056       colorstack.Pop();
01057                 
01058       // ENERGY BOX
01059       if( PowerPack::global_capacity > 0 )
01060         {
01061           colorstack.Push( 0.8,1.0,0.8,0.85 ); // pale green
01062           glRectf( 0, height, width, 90 );
01063           colorstack.Push( 0,0,0 ); // black
01064           Gl::draw_string_multiline( margin, height + margin, width, 50, 
01065                                      world->EnergyString().c_str(), 
01066                                      (Fl_Align)( FL_ALIGN_LEFT | FL_ALIGN_BOTTOM) );     
01067           colorstack.Pop();
01068           colorstack.Pop();
01069         }
01070                          
01071       glEnable( GL_DEPTH_TEST );
01072       glPopMatrix();
01073 
01074       //restore camera projection
01075       glMatrixMode (GL_PROJECTION);
01076       glPopMatrix();
01077       glMatrixMode (GL_MODELVIEW);
01078     }
01079 
01080   if( showScreenshots && (frames_rendered_count % screenshot_frame_skip == 0) )
01081     Screenshot();
01082 
01083   frames_rendered_count++; 
01084 }
01085 
01086 
01087 void Canvas::EnterScreenCS()
01088 {
01089   //use orthogonal projection without any zoom
01090   glMatrixMode (GL_PROJECTION);
01091   glPushMatrix(); //save old projection
01092   glLoadIdentity ();
01093   glOrtho( 0, w(), 0, h(), -100, 100 ); 
01094   glMatrixMode (GL_MODELVIEW);
01095   
01096   glPushMatrix();
01097   glLoadIdentity();
01098   glDisable( GL_DEPTH_TEST );
01099 }
01100 
01101 void Canvas::LeaveScreenCS()
01102 {
01103   glEnable( GL_DEPTH_TEST );
01104   glPopMatrix();
01105   glMatrixMode (GL_PROJECTION);
01106   glPopMatrix();
01107   glMatrixMode (GL_MODELVIEW);
01108 }
01109 
01110 
01111 void Canvas::Screenshot()
01112 {
01113 
01114   int width = w();
01115   int height = h();
01116   int depth = 4; // RGBA
01117 
01118   // we use RGBA throughout, though we only need RGB, as the 4-byte
01119   // pixels avoid a nasty word-alignment problem when indexing into
01120   // the pixel array.
01121 
01122   // might save a bit of time with a static var as the image size rarely changes
01123   static std::vector<uint8_t> pixels;
01124   pixels.resize( width * height * depth );
01125   
01126   glFlush(); // make sure the drawing is done
01127   // read the pixels from the screen
01128   glReadPixels( 0,0, width, height, GL_RGBA, GL_UNSIGNED_BYTE, &pixels[0] );                     
01129   
01130   static uint32_t count = 0;             
01131   char filename[64];
01132   snprintf( filename, 63, "stage-%06d.png", count++ );
01133   
01134   FILE *fp = fopen( filename, "wb" );
01135   if( fp == NULL ) 
01136     {
01137       PRINT_ERR1( "Unable to open %s", filename );
01138     }
01139   
01140   // create PNG data
01141   png_structp pp = png_create_write_struct(PNG_LIBPNG_VER_STRING, 0, 0, 0);
01142   assert(pp);
01143   png_infop info = png_create_info_struct(pp);
01144   assert(info);
01145 
01146   // setup the output file
01147   png_init_io(pp, fp);
01148 
01149   // need to invert the image as GL and PNG disagree on the row order
01150   png_bytep rowpointers[height];
01151   for( int i=0; i<height; i++ )
01152     rowpointers[i] = &pixels[ (height-1-i) * width * depth ];
01153 
01154   png_set_rows( pp, info, rowpointers ); 
01155 
01156   png_set_IHDR( pp, info, 
01157                 width, height, 8, 
01158                 PNG_COLOR_TYPE_RGBA, 
01159                 PNG_INTERLACE_NONE, 
01160                 PNG_COMPRESSION_TYPE_DEFAULT, 
01161                 PNG_FILTER_TYPE_DEFAULT);
01162 
01163   png_write_png( pp, info, PNG_TRANSFORM_IDENTITY, NULL );
01164 
01165   // free the PNG data - we reuse the pixel array next call.
01166   png_destroy_write_struct(&pp, &info);
01167   
01168   fclose(fp);
01169   
01170   printf( "Saved %s\n", filename );
01171 }
01172 
01173 void Canvas::perspectiveCb( Fl_Widget* w, void* p ) 
01174 {
01175   Canvas* canvas = static_cast<Canvas*>( w );
01176   Option* opt = static_cast<Option*>( p ); // pCamOn
01177   if ( opt ) {
01178     // Perspective mode is on, change camera
01179     canvas->current_camera = &canvas->perspective_camera;
01180   }
01181   else {
01182     canvas->current_camera = &canvas->camera;
01183   }
01184         
01185   canvas->invalidate();
01186 }
01187 
01188 void Canvas::createMenuItems( Fl_Menu_Bar* menu, std::string path )
01189 {
01190   showData.createMenuItem( menu, path );
01191   //  visualizeAll.createMenuItem( menu, path );
01192   showBlocks.createMenuItem( menu, path );
01193   showFlags.createMenuItem( menu, path );
01194   showClock.createMenuItem( menu, path );
01195   showFlags.createMenuItem( menu, path );
01196   showFollow.createMenuItem( menu, path );
01197   showFootprints.createMenuItem( menu, path );
01198   showGrid.createMenuItem( menu, path );
01199   showStatus.createMenuItem( menu, path );
01200   pCamOn.createMenuItem( menu, path );
01201   pCamOn.menuCallback( perspectiveCb, this );
01202   showOccupancy.createMenuItem( menu, path );
01203   showTrailArrows.createMenuItem( menu, path );
01204   showTrails.createMenuItem( menu, path ); 
01205   showTrailRise.createMenuItem( menu, path );  // broken
01206   showBBoxes.createMenuItem( menu, path );
01207   //showVoxels.createMenuItem( menu, path );  
01208   showScreenshots.createMenuItem( menu, path );  
01209 }
01210 
01211 
01212 void Canvas::Load( Worldfile* wf, int sec )
01213 {
01214   this->wf = wf;
01215   camera.Load( wf, sec );
01216   perspective_camera.Load( wf, sec );           
01217         
01218   interval = wf->ReadInt(sec, "interval", interval );
01219 
01220   screenshot_frame_skip = wf->ReadInt( sec, "screenshot_skip", screenshot_frame_skip );
01221   if( screenshot_frame_skip < 1 )
01222     screenshot_frame_skip = 1; // avoids div-by-zero if poorly set
01223 
01224   showData.Load( wf, sec );
01225   showFlags.Load( wf, sec );
01226   showBlocks.Load( wf, sec );
01227   showBBoxes.Load( wf, sec );
01228   showBlur.Load( wf, sec );
01229   showClock.Load( wf, sec );
01230   showFollow.Load( wf, sec );
01231   showFootprints.Load( wf, sec );
01232   showGrid.Load( wf, sec );
01233   showOccupancy.Load( wf, sec );
01234   showTrailArrows.Load( wf, sec );
01235   showTrailRise.Load( wf, sec );
01236   showTrails.Load( wf, sec );
01237   //showVoxels.Load( wf, sec );
01238   showScreenshots.Load( wf, sec );
01239   pCamOn.Load( wf, sec );
01240 
01241   if( ! world->paused )
01242     // // start the timer that causes regular redraws
01243     Fl::add_timeout( ((double)interval/1000), 
01244                      (Fl_Timeout_Handler)Canvas::TimerCallback, 
01245                      this);
01246 
01247   invalidate(); // we probably changed something
01248 }
01249 
01250 void Canvas::Save( Worldfile* wf, int sec )
01251 {
01252   camera.Save( wf, sec );
01253   perspective_camera.Save( wf, sec );   
01254         
01255   wf->WriteInt(sec, "interval", interval );
01256 
01257   showData.Save( wf, sec );
01258   showBlocks.Save( wf, sec );
01259   showBBoxes.Save( wf, sec );
01260   showBlur.Save( wf, sec );
01261   showClock.Save( wf, sec );
01262   showFlags.Save( wf, sec );
01263   showFollow.Save( wf, sec );
01264   showFootprints.Save( wf, sec );
01265   showGrid.Save( wf, sec );
01266   showOccupancy.Save( wf, sec );
01267   showTrailArrows.Save( wf, sec );
01268   showTrailRise.Save( wf, sec );
01269   showTrails.Save( wf, sec );
01270   showVoxels.Save( wf, sec );
01271   showScreenshots.Save( wf, sec );
01272   pCamOn.Save( wf, sec );
01273 }
01274 
01275 
01276 void Canvas::draw()
01277 {
01278   //Enable the following to debug camera model
01279   //    if( loaded_texture == true && pCamOn == true )
01280   //            return;
01281   
01282   if (!valid() ) 
01283     { 
01284       if( ! init_done )
01285         InitGl();
01286       if( ! texture_load_done )
01287         InitTextures();
01288                 
01289       if( pCamOn == true ) 
01290         {
01291           perspective_camera.setAspect( static_cast< float >( w() ) / static_cast< float >( h() ) );
01292           perspective_camera.SetProjection();
01293           current_camera = &perspective_camera;
01294         } 
01295       else 
01296         {
01297           bounds3d_t extent = world->GetExtent();
01298           camera.SetProjection( w(), h(), extent.y.min, extent.y.max );
01299           current_camera = &camera;
01300         }
01301                 
01302       glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT );
01303     }            
01304 
01305   //Follow the selected robot   
01306   if( showFollow  && last_selection ) 
01307     {
01308       Pose gpose = last_selection->GetGlobalPose();
01309       if( pCamOn == true )
01310         {
01311           perspective_camera.setPose( gpose.x, gpose.y, 0.2 );
01312           perspective_camera.setYaw( rtod( gpose.a ) - 90.0 );
01313         } 
01314       else 
01315         {
01316           camera.setPose( gpose.x, gpose.y );
01317         }
01318     }
01319   
01320   current_camera->Draw();       
01321   renderFrame();
01322 }
01323 
01324 void Canvas::resize(int X,int Y,int W,int H) 
01325 {
01326   Fl_Gl_Window::resize(X,Y,W,H);
01327 
01328   if( ! init_done ) // hack - should capture a create event to do this rather thann have it in multiple places
01329     InitGl();
01330         
01331   FixViewport(W,H);
01332   invalidate();
01333 }


stage
Author(s): Richard Vaughan , Brian Gerkey , Reed Hedges , Andrew Howard , Toby Collett , Pooya Karimian , Jeremy Asher , Alex Couture-Beil , Geoff Biggs , Rich Mattes , Abbas Sadat
autogenerated on Thu Aug 27 2015 15:20:57