display.h
Go to the documentation of this file.
00001 /* This file is part of the Pangolin Project.
00002  * http://github.com/stevenlovegrove/Pangolin
00003  *
00004  * Copyright (c) 2011 Steven Lovegrove, Richard Newcombe
00005  *
00006  * Permission is hereby granted, free of charge, to any person
00007  * obtaining a copy of this software and associated documentation
00008  * files (the "Software"), to deal in the Software without
00009  * restriction, including without limitation the rights to use,
00010  * copy, modify, merge, publish, distribute, sublicense, and/or sell
00011  * copies of the Software, and to permit persons to whom the
00012  * Software is furnished to do so, subject to the following
00013  * conditions:
00014  *
00015  * The above copyright notice and this permission notice shall be
00016  * included in all copies or substantial portions of the Software.
00017  *
00018  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
00019  * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
00020  * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
00021  * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
00022  * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
00023  * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
00024  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
00025  * OTHER DEALINGS IN THE SOFTWARE.
00026  */
00027 
00028 #ifndef PANGOLIN_DISPLAY_H
00029 #define PANGOLIN_DISPLAY_H
00030 
00031 #include "platform.h"
00032 #include <string>
00033 #include <map>
00034 #include <vector>
00035 #include <cmath>
00036 #include <iostream>
00037 #include <boost/function.hpp>
00038 
00039 #ifdef HAVE_GLUT
00040 
00041 #ifdef HAVE_APPLE_OPENGL_FRAMEWORK
00042 #include <GLUT/glut.h>
00043 #define HAVE_GLUT_APPLE_FRAMEWORK
00044 
00045 inline void glutBitmapString(void* font, const unsigned char* str)
00046 {
00047     const unsigned char* s = str;
00048     while(*s != 0)
00049     {
00050         glutBitmapCharacter(font, *s);
00051         ++s;
00052     }
00053 }
00054 #else
00055 #include <GL/freeglut.h>
00056 #endif
00057 
00058 #endif // HAVE_GLUT
00059 
00060 #ifdef HAVE_TOON
00061 #include <cstring>
00062 #include <TooN/TooN.h>
00063 #include <TooN/se3.h>
00064 #endif
00065 
00066 #ifdef HAVE_EIGEN
00067 #include <Eigen/Eigen>
00068 #endif
00069 
00070 #ifdef _WIN_
00071 #include <Windows.h>
00072 #endif
00073 
00074 #include <GL/gl.h>
00075 
00076 #define GLUT_KEY_ESCAPE 27
00077 #define GLUT_KEY_TAB 9
00078 
00079 namespace pangolin
00080 {
00081 
00087 void BindToContext(std::string name);
00088 
00090 void Quit();
00091 
00093 bool ShouldQuit();
00094 
00096 bool HadInput();
00097 
00099 bool HasResized();
00100 
00102 void RenderViews();
00103 
00106 void RegisterKeyPressCallback(int key, boost::function<void(void)> func);
00107 
00108 // Supported Key modifiers for GlobalKeyPressCallback.
00109 // e.g. PANGO_CTRL + 'r', PANGO_SPECIAL + GLUT_KEY_RIGHT, etc.
00110 const int PANGO_SPECIAL = 128;
00111 const int PANGO_CTRL = -96;
00112 const int PANGO_OPTN = 132;
00113 
00114 namespace process
00115 {
00119 void Keyboard( unsigned char key, int x, int y);
00120 
00121 void KeyboardUp(unsigned char key, int x, int y);
00122 
00126 void Resize(int width, int height);
00127 
00128 void Mouse( int button, int state, int x, int y);
00129 
00130 void MouseMotion( int x, int y);
00131 
00132 void Scroll(float x, float y);
00133 }
00134 
00135 #ifdef HAVE_GLUT
00136 
00137 
00138 
00139 void CreateGlutWindowAndBind(std::string window_title, int w = 640, int h = 480, unsigned int mode = GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH );
00140 
00144 void FinishGlutFrame();
00145 
00147 void SwapGlutBuffersProcessGlutEvents();
00148 
00151 void TakeGlutCallbacks();
00152 #endif
00153 
00155 enum Unit
00156 {
00157     Fraction,
00158     Pixel,
00159     ReversePixel
00160 };
00161 
00165 struct Attach
00166 {
00167     Attach() : unit(Fraction), p(0) {}
00168     Attach(Unit unit, GLfloat p) : unit(unit), p(p) {}
00169 
00170     Attach(GLfloat p) : unit(Fraction), p(p)
00171     {
00172         if( p < 0 || 1.0 < p )
00173         {
00174             std::cerr << "Pangolin API Change: Display::SetBounds must be used with Attach::Pix or Attach::ReversePix to specify pixel bounds relative to an edge. See the code samples for details." << std::endl;
00175             throw std::exception();
00176         }
00177     }
00178 
00179 //    Attach(GLdouble p) : unit(Fraction), p(p) {}
00180 
00181     static Attach Pix(int p)
00182     {
00183         return Attach(p >=0 ? Pixel : ReversePixel, std::abs((float)p));
00184     }
00185     static Attach ReversePix(int p)
00186     {
00187         return Attach(ReversePixel, p);
00188     }
00189     static Attach Frac(float frac)
00190     {
00191         return Attach(frac);
00192     }
00193 
00194     Unit unit;
00195     GLfloat p;
00196 
00197 //  protected:
00198 //    Attach(int p) {}
00199 };
00200 
00201 
00202 enum Lock
00203 {
00204     LockLeft = 0,
00205     LockBottom = 0,
00206     LockCenter = 1,
00207     LockRight = 2,
00208     LockTop = 2
00209 };
00210 
00212 struct Viewport
00213 {
00214     Viewport() {}
00215     Viewport(GLint l,GLint b,GLint w,GLint h);
00216     void Activate() const;
00217     void Scissor() const;
00218     void ActivateAndScissor() const;
00219     bool Contains(int x, int y) const;
00220 
00221     Viewport Inset(int i) const;
00222     Viewport Inset(int horiz, int vert) const;
00223 
00224     static void DisableScissor();
00225 
00226     GLint r() const;
00227     GLint t() const;
00228     GLfloat aspect() const;
00229     GLint l,b,w,h;
00230 };
00231 
00233 enum OpenGlStack
00234 {
00235     GlProjectionStack = GL_PROJECTION,
00236     GlModelViewStack = GL_MODELVIEW,
00237     GlTextureStack = GL_TEXTURE
00238 };
00239 
00240 struct CameraSpec
00241 {
00242     GLdouble forward[3];
00243     GLdouble up[3];
00244     GLdouble right[3];
00245     GLdouble img_up[2];
00246     GLdouble img_right[2];
00247 };
00248 
00249 const static CameraSpec CameraSpecOpenGl = {{0,0,-1},{0,1,0},{1,0,0},{0,1},{1,0}};
00250 const static CameraSpec CameraSpecYDownZForward = {{0,0,1},{0,-1,0},{1,0,0},{0,-1},{1,0}};
00251 
00253 struct OpenGlMatrix
00254 {
00255     OpenGlMatrix();
00256 
00257 #ifdef HAVE_EIGEN
00258     template<typename P>
00259     OpenGlMatrix(const Eigen::Matrix<P,4,4>& mat);
00260 
00261     template<typename P>
00262     operator Eigen::Matrix<P,4,4>() const;
00263 #endif // HAVE_EIGEN
00264 
00265     // Load matrix on to OpenGl stack
00266     void Load() const;
00267 
00268     void Multiply() const;
00269 
00270     void SetIdentity();
00271 
00272     // Column major Internal buffer
00273     GLdouble m[16];
00274 };
00275 
00277 struct OpenGlMatrixSpec : public OpenGlMatrix
00278 {
00279     // Specify which stack this refers to
00280     OpenGlStack type;
00281 };
00282 
00286 struct OpenGlRenderState
00287 {
00288     OpenGlRenderState();
00289     OpenGlRenderState(const OpenGlMatrix& projection_matrix);
00290     OpenGlRenderState(const OpenGlMatrix& projection_matrix, const OpenGlMatrix& modelview_matrix);
00291 
00292     static void ApplyIdentity();
00293     static void ApplyWindowCoords();
00294 
00295     void Apply() const;
00296     OpenGlRenderState& SetProjectionMatrix(OpenGlMatrix spec);
00297     OpenGlRenderState& SetModelViewMatrix(OpenGlMatrix spec);
00298 
00299     OpenGlMatrix& GetProjectionMatrix();
00300     OpenGlMatrix GetProjectionMatrix() const;
00301 
00302     OpenGlMatrix& GetModelViewMatrix();
00303     OpenGlMatrix GetModelViewMatrix() const;
00304 
00306     OpenGlRenderState& Set(OpenGlMatrixSpec spec);
00307 
00308     std::map<OpenGlStack,OpenGlMatrix> stacks;
00309 };
00310 
00311 enum Layout
00312 {
00313     LayoutOverlay,
00314     LayoutVertical,
00315     LayoutHorizontal,
00316     LayoutEqual
00317 };
00318 
00319 // Forward declaration
00320 struct Handler;
00321 
00323 struct View
00324 {
00325     View()
00326         : aspect(0.0), top(1.0),left(0.0),right(1.0),bottom(0.0), hlock(LockCenter),vlock(LockCenter),
00327           layout(LayoutOverlay), scroll_offset(0), show(1), handler(0), extern_draw_function(0) {}
00328 
00329     virtual ~View() {}
00330 
00332     void Activate() const;
00333 
00335     void Activate(const OpenGlRenderState& state ) const;
00336 
00338     void ActivateAndScissor() const;
00339 
00341     void ActivateScissorAndClear() const;
00342 
00344     void ActivateAndScissor(const OpenGlRenderState& state ) const;
00345 
00347     void ActivateScissorAndClear(const OpenGlRenderState& state ) const;
00348 
00350     GLfloat GetClosestDepth(int winx, int winy, int radius) const;
00351 
00354     void GetCamCoordinates(const OpenGlRenderState& cam_state, double winx, double winy, double winzdepth, double& x, double& y, double& z) const;
00355 
00358     void GetObjectCoordinates(const OpenGlRenderState& cam_state, double winx, double winy, double winzdepth, double& x, double& y, double& z) const;
00359 
00361     virtual void Resize(const Viewport& parent);
00362 
00364     virtual void ResizeChildren();
00365 
00368     virtual void Render();
00369 
00371     virtual void RenderChildren();
00372 
00374     View& SetFocus();
00375 
00377     View& SetBounds(Attach bottom, Attach top, Attach left, Attach right, bool keep_aspect = false);
00378 
00380     View& SetBounds(Attach bottom, Attach top, Attach left, Attach right, double aspect);
00381 
00383     View& SetHandler(Handler* handler);
00384 
00386     View& SetDrawFunction(const boost::function<void(View&)>& drawFunc);
00387 
00391     View& SetAspect(double aspect);
00392 
00394     View& SetLock(Lock horizontal, Lock vertical );
00395 
00397     View& SetLayout(Layout layout);
00398 
00400     View& AddDisplay(View& view);
00401 
00403     View& operator[](int i);
00404 
00405     // Desired width / height aspect (0 if dynamic)
00406     double aspect;
00407 
00408     // Bounds to fit display within
00409     Attach top, left, right, bottom;
00410     Lock hlock;
00411     Lock vlock;
00412     Layout layout;
00413 
00414     int scroll_offset;
00415 
00416     // Cached client area (space allocated from parent)
00417     Viewport vp;
00418 
00419     // Cached absolute viewport (recomputed on resize - respects aspect)
00420     Viewport v;
00421 
00422     // Should this view be displayed?
00423     bool show;
00424 
00425     // Input event handler (if any)
00426     Handler* handler;
00427 
00428     // Map for sub-displays (if any)
00429     std::vector<View*> views;
00430 
00431     // External draw function
00432     boost::function<void(View&)> extern_draw_function;
00433 
00434 private:
00435     // Private copy constructor
00436     View(View&)
00437     {
00438         /* Do Not copy - take reference instead*/
00439     }
00440 };
00441 
00442 enum MouseButton
00443 {
00444     MouseButtonLeft = 1,
00445     MouseButtonMiddle = 2,
00446     MouseButtonRight = 4,
00447     MouseWheelUp = 8,
00448     MouseWheelDown = 16
00449 };
00450 
00453 struct Handler
00454 {
00455     virtual ~Handler() {}
00456     virtual void Keyboard(View&, unsigned char key, int x, int y, bool pressed);
00457     virtual void Mouse(View&, MouseButton button, int x, int y, bool pressed, int button_state);
00458     virtual void MouseMotion(View&, int x, int y, int button_state);
00459 };
00460 static Handler StaticHandler;
00461 
00462 struct HandlerScroll : Handler
00463 {
00464     void Mouse(View&, MouseButton button, int x, int y, bool pressed, int button_state);
00465 };
00466 static HandlerScroll StaticHandlerScroll;
00467 
00468 enum AxisDirection
00469 {
00470     AxisNone,
00471     AxisNegX, AxisX,
00472     AxisNegY, AxisY,
00473     AxisNegZ, AxisZ
00474 };
00475 
00476 struct Handler3D : Handler
00477 {
00478 
00479     Handler3D(OpenGlRenderState& cam_state, AxisDirection enforce_up=AxisNone, float trans_scale=0.01f)
00480         : cam_state(&cam_state), enforce_up(enforce_up), tf(trans_scale), cameraspec(CameraSpecOpenGl), last_z(1.0) {}
00481 
00482     void Keyboard(View&, unsigned char key, int x, int y, bool pressed);
00483     void Mouse(View&, MouseButton button, int x, int y, bool pressed, int button_state);
00484     void MouseMotion(View&, int x, int y, int button_state);
00485 
00486 protected:
00487     OpenGlRenderState* cam_state;
00488     const static int hwin = 8;
00489     AxisDirection enforce_up;
00490     float tf;
00491     CameraSpec cameraspec;
00492     GLfloat last_z;
00493     GLint last_pos[2];
00494     GLdouble rot_center[3];
00495 };
00496 
00498 View& DisplayBase();
00499 
00501 View& Display(const std::string& name);
00502 
00504 View& CreateDisplay();
00505 
00506 OpenGlMatrixSpec ProjectionMatrixRUB_BottomLeft(int w, int h, double fu, double fv, double u0, double v0, double zNear, double zFar );
00507 OpenGlMatrixSpec ProjectionMatrixRDF_TopLeft(int w, int h, double fu, double fv, double u0, double v0, double zNear, double zFar );
00508 OpenGlMatrixSpec ProjectionMatrixRDF_BottomLeft(int w, int h, double fu, double fv, double u0, double v0, double zNear, double zFar );
00509 
00511 OpenGlMatrixSpec ProjectionMatrix(int w, int h, double fu, double fv, double u0, double v0, double zNear, double zFar );
00512 OpenGlMatrixSpec ProjectionMatrixOrthographic(double t, double b, double l, double r, double n, double f );
00513 
00516 OpenGlMatrix ModelViewLookAt(double x, double y, double z, double lx, double ly, double lz, AxisDirection up);
00517 OpenGlMatrix ModelViewLookAt(double ex, double ey, double ez, double lx, double ly, double lz, double ux, double uy, double uz);
00518 
00519 OpenGlMatrix IdentityMatrix();
00520 OpenGlMatrixSpec IdentityMatrix(OpenGlStack type);
00521 OpenGlMatrixSpec negIdentityMatrix(OpenGlStack type);
00522 
00523 #ifdef HAVE_TOON
00524 OpenGlMatrixSpec FromTooN(const TooN::SE3<>& T_cw);
00525 OpenGlMatrixSpec FromTooN(OpenGlStack type, const TooN::Matrix<4,4>& M);
00526 TooN::Matrix<4,4> ToTooN(const OpenGlMatrixSpec& ms);
00527 TooN::SE3<> ToTooN_SE3(const OpenGlMatrixSpec& ms);
00528 #endif
00529 
00530 
00531 }
00532 
00533 // Inline definitions
00534 namespace pangolin
00535 {
00536 
00537 inline Viewport::Viewport(GLint l,GLint b,GLint w,GLint h) : l(l),b(b),w(w),h(h) {}
00538 inline GLint Viewport::r() const
00539 {
00540     return l+w;
00541 }
00542 inline GLint Viewport::t() const
00543 {
00544     return b+h;
00545 }
00546 inline GLfloat Viewport::aspect() const
00547 {
00548     return (GLfloat)w / (GLfloat)h;
00549 }
00550 
00551 
00552 inline OpenGlMatrix::OpenGlMatrix()
00553 {
00554 }
00555 
00556 #ifdef HAVE_EIGEN
00557 template<typename P> inline
00558 OpenGlMatrix::OpenGlMatrix(const Eigen::Matrix<P,4,4>& mat)
00559 {
00560     for(int r=0; r<4; ++r )
00561     {
00562         for(int c=0; c<4; ++c )
00563         {
00564             m[c*4+r] = mat(r,c);
00565         }
00566     }
00567 }
00568 
00569 template<typename P>
00570 OpenGlMatrix::operator Eigen::Matrix<P,4,4>() const
00571 {
00572     Eigen::Matrix<P,4,4> mat;
00573     for(int r=0; r<4; ++r )
00574     {
00575         for(int c=0; c<4; ++c )
00576         {
00577             mat(r,c) = m[c*4+r];
00578         }
00579     }
00580     return mat;
00581 }
00582 
00583 #endif
00584 
00585 #ifdef HAVE_TOON
00586 
00587 inline OpenGlMatrixSpec FromTooN(const TooN::SE3<>& T_cw)
00588 {
00589     TooN::Matrix<4,4,double,TooN::ColMajor> M;
00590     M.slice<0,0,3,3>() = T_cw.get_rotation().get_matrix();
00591     M.T()[3].slice<0,3>() = T_cw.get_translation();
00592     M[3] = TooN::makeVector(0,0,0,1);
00593 
00594     OpenGlMatrixSpec P;
00595     P.type = GlModelViewStack;
00596     std::memcpy(P.m, &(M[0][0]),16*sizeof(double));
00597     return P;
00598 }
00599 
00600 inline OpenGlMatrixSpec FromTooN(OpenGlStack type, const TooN::Matrix<4,4>& M)
00601 {
00602     // Read in remembering col-major convension for our matrices
00603     OpenGlMatrixSpec P;
00604     P.type = type;
00605     int el = 0;
00606     for(int c=0; c<4; ++c)
00607         for(int r=0; r<4; ++r)
00608             P.m[el++] = M[r][c];
00609     return P;
00610 }
00611 
00612 inline TooN::Matrix<4,4> ToTooN(const OpenGlMatrixSpec& ms)
00613 {
00614     TooN::Matrix<4,4> m;
00615     int el = 0;
00616     for( int c=0; c<4; ++c )
00617         for( int r=0; r<4; ++r )
00618             m(r,c) = ms.m[el++];
00619     return m;
00620 }
00621 
00622 inline TooN::SE3<> ToTooN_SE3(const OpenGlMatrixSpec& ms)
00623 {
00624     TooN::Matrix<4,4> m = ToTooN(ms);
00625     const TooN::SO3<> R(m.slice<0,0,3,3>());
00626     const TooN::Vector<3> t = m.T()[3].slice<0,3>();
00627     return TooN::SE3<>(R,t);
00628 }
00629 
00630 
00631 #endif
00632 
00633 }
00634 
00635 #endif // PANGOLIN_DISPLAY_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pangolin_wrapper
Author(s): Todor Stoyanov
autogenerated on Wed Feb 13 2013 14:03:25