renderworld.cpp
1 /********************************************************************************
2  * WorldSim -- library for robot simulations *
3  * Copyright (C) 2008-2011 Gianluca Massera <emmegian@yahoo.it> *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the GNU General Public License as published by *
7  * the Free Software Foundation; either version 2 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the GNU General Public License *
16  * along with this program; if not, write to the Free Software *
17  * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA *
18  ********************************************************************************/
19 
20 #include "renderworld.h"
21 #include "phyjoint.h"
22 
23 #include <QImage>
24 #include <QColor>
25 #include <QKeyEvent>
26 #include <QMenu>
27 #include <QAction>
28 #include <QList>
29 #include <cmath>
30 #include <QDir>
31 #include <QLinkedList>
32 #include <QMutexLocker>
33 #include <QEvent>
34 #include <QGLWidget>
35 
36 // These instructions are needed because QT 4.8 no longer depends on glu, so we
37 // have to include it here explicitly
38 #ifdef FARSA_MAC
39 # include <GLUT/glut.h>
40 #else
41 # include <GL/glu.h>
42 #endif
43 
44 using namespace qglviewer;
45 
46 #define GLMultMatrix glMultMatrixf
47 #define GLTranslate glTranslatef
48 // for double use #define GLMultMatrix glMultMatrixd and #define GLTranslate glTranslated
49 
50 #include "qglviewer/camera.h"
51 #include "qglviewer/manipulatedCameraFrame.h"
52 #if QT_VERSION >= 0x040000
53 # include <QWheelEvent>
54 #endif
55 
56 namespace farsa {
57 
58 void RenderWObject::drawLabel()
59 {
60  if (!obj->labelShown() || (obj->label().isEmpty())) {
61  return;
62  }
63 
64  // We can only draw text through QGLWidget, so if this cast fails, we quit
65  QGLWidget* qglwidget = dynamic_cast<QGLWidget*>(container());
66  if (qglwidget == NULL) {
67  return;
68  }
69 
70  // Setting color
71  glPushAttrib(GL_LIGHTING_BIT | GL_DEPTH_BUFFER_BIT);
72  glDisable(GL_LIGHTING);
73  glDisable(GL_DEPTH_TEST);
74  const QColor& lcol = obj->labelColor();
75  glColor4f(lcol.redF(), lcol.greenF(), lcol.blueF(), lcol.alphaF());
76 
77  // Drawing text
78  const wVector lpos = obj->labelPosition();
79  qglwidget->renderText(lpos.x, lpos.y, lpos.z, obj->label());
80 
81  glPopAttrib();
82 }
83 
84 QMap<QString, QImage>* RenderWObjectContainer::textmap = NULL;
85 unsigned int RenderWObjectContainer::textmapRefCounter = 0;
86 QMutex RenderWObjectContainer::textmapMutex(QMutex::Recursive);
87 
88 RenderWObjectContainer::RenderWObjectContainer( QString wResName ) :
89  mutex(QMutex::Recursive),
90  worldResourceName(wResName),
91  worldv(NULL)
92 {
93  QMutexLocker locker(&textmapMutex);
94 
95  initializeTextmap();
96 
97  textmapRefCounter++;
98 
99  usableResources(QStringList() << worldResourceName);
100 }
101 
103  foreach( RenderWObject* ro, graphs ) {
104  delete ro;
105  }
106 
107  QMutexLocker locker(&textmapMutex);
108  textmapRefCounter--;
109  if (textmapRefCounter == 0) {
110  delete textmap;
111  textmap = NULL;
112  }
113 }
114 
115 bool RenderWObjectContainer::addTextureImage( QString filename, QString texturename ) {
116  QMutexLocker locker(&textmapMutex);
117 
118  initializeTextmap();
119 
120  return (*textmap)[texturename].load(filename);
121 }
122 
124  // Here we simply declare a resource, the resourceChanged handler will take care of setting things up
125  declareResource( worldResourceName, newworld );
126 }
127 
129  QMutexLocker locker(&mutex);
130 
131  //--- not efficient !! OPTIMIZE ME
132  for( int i=0; i<graphs.size(); i++ ) {
133  if ( graphs[i]->object() == obj ) {
134  return graphs[i];
135  }
136  }
137  return NULL;
138 }
139 
141  initFactory();
142  const QMetaObject* metaObj = obj->metaObject();
143  while( metaObj ) {
144  QString classname = metaObj->className();
145  if (fac->contains(classname)) {
146  return (*fac)[classname]->create( (WObject*)obj, container );
147  }
148  metaObj = metaObj->superClass();
149  }
150 
151  // Cannot find a specific renderer, using the generic one (which doesn't render anything...
152  // at least we save a crash)
153  return (*fac)["farsa::WObject"]->create( (WObject*)obj, container );
154 }
155 
157  // Always take the resource mutex first and then our mutex to avoid deadlocks
158  ResourcesLocker resourceLocker(this); // Here because perhaps the RenderWObject need to access the world
159  QMutexLocker locker(&mutex);
160 
161  graphs.append( createRenderWObjectFor( wobj, this ) );
162 }
163 
165  // Always take the resource mutex first and then our mutex to avoid deadlocks
166  ResourcesLocker resourceLocker(this); // Here because perhaps the RenderWObject need to access the world
167  QMutexLocker locker(&mutex);
168 
169  for( int i=0; i<graphs.size(); i++ ) {
170  if ( graphs[i]->object() == wobj ) {
171  RenderWObject* ro = graphs[i];
172  graphs.remove( i );
174  delete ro;
175  break;
176  }
177  }
178 }
179 
181 {
182  QMutexLocker locker(&mutex);
183 
184  // We ignore all resources except world
185  if (name != worldResourceName) {
186  return;
187  }
188 
189  // Removing all objects, they refer to the old world
190  foreach( RenderWObject* ro, graphs ) {
191  delete ro;
192  }
193  graphs.clear();
194 
195  // If world was deleted, we simply set the pointer to NULL, otherwise we set the pointer
196  // to the new world
197  if (changeType == Deleted) {
198  worldv = NULL;
199  } else {
200  worldv = getResource<World>();
201  }
202 
203  // Creating renderes for all objects
204  if (worldv != NULL) {
205  foreach( WObject* obj, worldv->objects() ) {
206  graphs.append( createRenderWObjectFor( obj, this ) );
207  }
208  }
209 }
210 
211 void RenderWObjectContainer::initializeTextmap()
212 {
213  if ( textmap == NULL ) {
214  textmap = new QMap<QString, QImage>();
215  (*textmap)["tile1"].load( ":/tiles/16tile10.jpg" );
216  (*textmap)["tile2"].load( ":/tiles/16tile07.jpg" );
217  (*textmap)["white"].load( ":/white.jpg" );
218  (*textmap)["tile3"].load( ":/tiles/16tile11.jpg" );
219  (*textmap)["tile4"].load( ":/tiles/16tile-B.jpg" );
220  (*textmap)["tile5"].load( ":/tiles/16tile12.jpg" );
221  (*textmap)["tile6"].load( ":/tiles/16tile04.jpg" );
222  (*textmap)["tile7"].load( ":/tiles/tile01.jpg" );
223  (*textmap)["tile8"].load( ":/tiles/16tile02.jpg" );
224  (*textmap)["tile9"].load( ":/tiles/16tile05.jpg" );
225  (*textmap)["tile10"].load( ":/tiles/16tile08.jpg" );
226  (*textmap)["icub"].load( ":/tiles/16tile11.jpg" ); //.load( ":/metal/iron05.jpg" );
227  (*textmap)["icubFace"].load( ":/covers/face.jpg" );
228  (*textmap)["blueye"].load( ":/covers/eyep2_b.jpg" );
229  (*textmap)["metal"].load( ":/metal/iron05.jpg" );
230  (*textmap)["marXbot_12leds"].load( ":/covers/marxbot_12leds.jpg" );
231  //--- The order of the texture is:
232  // 0 => TOP
233  // 1 => BACK
234  // 2 => FRONT
235  // 3 => BOTTOM
236  // 4 => RIGHT
237  // 5 => LEFT
238  /* skyb[0].load( ":/skybox/sb_top.jpg" );
239  skyb[1].load( ":/skybox/sb_back.jpg" );
240  skyb[2].load( ":/skybox/sb_front.jpg" );
241  skyb[3].load( ":/skybox/sb_bottom.jpg" );
242  skyb[4].load( ":/skybox/sb_right.jpg" );
243  skyb[5].load( ":/skybox/sb_left.jpg" );*/
244  (*textmap)["skyb0"].load( ":/skybox/sb2_top.jpg" );
245  (*textmap)["skyb1"].load( ":/skybox/sb2_back.jpg" );
246  (*textmap)["skyb2"].load( ":/skybox/sb2_front.jpg" );
247  (*textmap)["skyb3"].load( ":/ground/cobbles01.jpg" );
248  (*textmap)["skyb4"].load( ":/skybox/sb2_right.jpg" );
249  (*textmap)["skyb5"].load( ":/skybox/sb2_left.jpg" );
250  }
251 }
252 
253 void RenderWObjectContainer::applyTexture( QGLContext* gw, QString texts ) {
254  QMutexLocker locker(&mutex);
255  QMutexLocker textmapLocker(&textmapMutex);
256 
257  if ( textmap->contains( texts ) ) {
258  if ( !textGLId.contains( texts ) ) {
259  textGLId[texts] = gw->bindTexture( (*textmap)[texts], GL_TEXTURE_2D, GL_RGB );
260  }
261  glBindTexture( GL_TEXTURE_2D, textGLId[texts] );
262  glEnable( GL_TEXTURE_2D );
263  }/* else {
264  glDisable( GL_TEXTURE_2D );
265  }*/
266 }
267 
269  // Always take the resource mutex first and then our mutex to avoid deadlocks
270  ResourcesLocker resourceLocker(this);
271  QMutexLocker locker(&mutex);
272 
273  // set the color
274  glShadeModel( GL_SMOOTH );
275  glEnable( GL_BLEND );
276  glBlendFunc( GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA );
277  WObject* obj = robj->object();
278  while ( obj->useColorTextureOfOwner() && ( obj->owner() != NULL ) ) {
279  WObject *const owner = dynamic_cast<WObject *>(obj->owner());
280  if ( owner != NULL ) {
281  obj = owner;
282  } else {
283  break;
284  }
285  }
286  QColor colorv = obj->color();
287  glColor4f( colorv.redF(), colorv.greenF(), colorv.blueF(), colorv.alphaF() );
288  applyTexture( gw, obj->texture() );
289 }
290 
292  // Always take the resource mutex first and then our mutex to avoid deadlocks
293  ResourcesLocker resourceLocker(this);
294  QMutexLocker locker(&mutex);
295 
296  if (worldv == NULL) {
297  return;
298  }
299  wVector min, max;
300  worldv->size( min, max );
301  wVector m_size = wVector( fabs(max[0]-min[0]), fabs(max[1]-min[1]), fabs(max[1]-min[1]) );
302 
303  resourceLocker.unlock(); // We don't need it anymore
304 
305  glDisable( GL_LIGHTING );
306  glShadeModel( GL_FLAT );
307  glColor4f( 1.0f, 1.0f, 1.0f, 1.0f );
308  //glEnable(GL_TEXTURE_2D);
309  //glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT);
310  //glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT);
311  //glTexEnvf (GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_DECAL);
312  // the cube will just be drawn as six quads for the sake of simplicity
313  // for each face, we specify the quad's normal (for lighting), then
314  // specify the quad's 4 vertices's and associated texture coordinates
315  // TOP
316  applyTexture( gw, "skyb0" );
317  glBegin(GL_QUADS);
318  glTexCoord2f(0.0, 1.0); glVertex3f( min.x, max.y, max.z);
319  glTexCoord2f(0.0, 0.0); glVertex3f( max.x, max.y, max.z);
320  glTexCoord2f(1.0, 0.0); glVertex3f( max.x, min.y, max.z);
321  glTexCoord2f(1.0, 1.0); glVertex3f( min.x, min.y, max.z);
322  glEnd();
323  // BACK
324  applyTexture( gw, "skyb1" );
325  glBegin(GL_QUADS);
326  glTexCoord2f(1.0, 0.0); glVertex3f( min.x, max.y, min.z);
327  glTexCoord2f(1.0, 1.0); glVertex3f( min.x, max.y, max.z);
328  glTexCoord2f(0.0, 1.0); glVertex3f( min.x, min.y, max.z);
329  glTexCoord2f(0.0, 0.0); glVertex3f( min.x, min.y, min.z);
330  glEnd();
331  // FRONT
332  applyTexture( gw, "skyb2" );
333  glBegin(GL_QUADS);
334  glTexCoord2f(0.0, 1.0); glVertex3f(max.x, max.y, max.z);
335  glTexCoord2f(0.0, 0.0); glVertex3f(max.x, max.y, min.z);
336  glTexCoord2f(1.0, 0.0); glVertex3f(max.x, min.y, min.z);
337  glTexCoord2f(1.0, 1.0); glVertex3f(max.x, min.y, max.z);
338  glEnd();
339  // BOTTOM
340  applyTexture( gw, "skyb3" );
341  //--- suppose the bottom texture will represent 40x40 cm of ground
342  //--- and calculate repeating accordlying
343  float bfs = m_size[1]/0.4;
344  float bft = m_size[0]/0.4;
345  glBegin(GL_QUADS);
346  glTexCoord2f(0.0, bft); glVertex3f( max.x, max.y, min.z);
347  glTexCoord2f(0.0, 0.0); glVertex3f( min.x, max.y, min.z);
348  glTexCoord2f(bfs, 0.0); glVertex3f( min.x, min.y, min.z);
349  glTexCoord2f(bfs, bft); glVertex3f( max.x, min.y, min.z);
350  glEnd();
351  // RIGHT
352  applyTexture( gw, "skyb4" );
353  glBegin(GL_QUADS);
354  glTexCoord2f(1.0, 1.0); glVertex3f( min.x, min.y, max.z);
355  glTexCoord2f(0.0, 1.0); glVertex3f( max.x, min.y, max.z);
356  glTexCoord2f(0.0, 0.0); glVertex3f( max.x, min.y, min.z);
357  glTexCoord2f(1.0, 0.0); glVertex3f( min.x, min.y, min.z);
358  glEnd();
359  // LEFT
360  applyTexture( gw, "skyb5" );
361  glBegin(GL_QUADS);
362  glTexCoord2f(0.0, 0.0); glVertex3f( min.x, max.y, min.z);
363  glTexCoord2f(1.0, 0.0); glVertex3f( max.x, max.y, min.z);
364  glTexCoord2f(1.0, 1.0); glVertex3f( max.x, max.y, max.z);
365  glTexCoord2f(0.0, 1.0); glVertex3f( min.x, max.y, max.z);
366  glEnd();
367 }
368 
370 public :
371  StandardCamera() {
372  orthoSize = 1.0;
373  };
374  virtual float zNear() const {
375  return 0.001f;
376  };
377  virtual float zFar() const {
378  return 1000.0f;
379  };
380  void changeOrthoFrustumSize(int delta) {
381  if (delta > 0) {
382  orthoSize *= 1.1f;
383  } else {
384  orthoSize /= 1.1f;
385  }
386  };
387  virtual void getOrthoWidthHeight(GLdouble &halfWidth, GLdouble &halfHeight) const {
388  halfHeight = orthoSize;
389  halfWidth = aspectRatio() * orthoSize;
390  };
391 private :
392  float orthoSize;
393 };
394 
396 public:
399  //--- the pad allow to avoid to reach exactly the bounding-box of the world
400  qglviewer::Vec pad(0.1,0.1,0.1);
401  minP = min + pad;
402  maxP = max - pad;
403  };
404  virtual void constrainTranslation( qglviewer::Vec& t, qglviewer::Frame* const fr ) {
405  //--- Local System
406  const qglviewer::Frame* ls = fr;
407  if ( fr->referenceFrame() != NULL ) {
408  qDebug() << "Using Reference";
409  ls = fr->referenceFrame();
410  }
411  //--- Convert t to world coordinate system
412  qglviewer::Vec tw = ls->inverseTransformOf( t );
413  qglviewer::Vec pos = fr->position();
414  if ( (pos.x + tw.x > maxP.x && t.x > 0) || (pos.x + tw.x < minP.x && t.x < 0) ||
415  (pos.y + tw.y > maxP.y && t.y > 0) || (pos.y + tw.y < minP.y && t.y < 0) ||
416  (pos.z + tw.z > maxP.z && t.z > 0) || (pos.z + tw.z < minP.z && t.z < 0) ) {
417  t.z = 0.0;
418  t.x = 0.0;
419  t.y = 0.0;
420  }
421  };
422  //--- boundings
423  qglviewer::Vec minP;
424  qglviewer::Vec maxP;
425 };
426 
427 namespace {
428  // A custom QEvent to force update of RenderWorldWrapperWidget
429  class ForceRenderWorldUpdateEvent : public QEvent
430  {
431  public:
432  ForceRenderWorldUpdateEvent() :
433  QEvent(QEvent::User)
434  {
435  }
436 
437  virtual ~ForceRenderWorldUpdateEvent()
438  {
439  }
440  };
441 }
442 
443 
444 RenderWorld::RenderWorld( QWidget* parent, QString wResName )
445  : QGLViewer( parent ), RenderWObjectContainer( wResName ) {
446  wiref = false;
447  showskygroundbox = true;
448  showobjs = true;
449  showjoints = false;
450  showaabbs = false;
451  showcontacts = true;
452  showforces = false;
453  showlocalaxes = false;
454  showlabels = false;
455  showtimeandstep = true;
456  currentSelected = -1;
457 
458  setStateFileName( QString() );
459 
460  setCamera( new StandardCamera() );
461 
462  setContextMenuPolicy( Qt::CustomContextMenu );
463 }
464 
466  if ( ! stateFileName().isNull() ) {
467  saveStateToFile();
468  }
469 }
470 
471 void RenderWorld::slotRemoveObject( WObject* w ) {
472  // removeObject is already thread-safe, no need to lock mutex here
473  removeObject( w );
474 }
475 
476 void RenderWorld::slotAddObject( WObject* w ) {
477  // removeObject is already thread-safe, no need to lock mutex here
478  addObject( w );
479 }
480 
481 void RenderWorld::onWorldResize() {
482  // Always take the resource mutex first and then our mutex to avoid deadlocks
483  ResourcesLocker resourceLocker(this);
484  QMutexLocker locker(&mutex);
485 
486  if (world() == NULL) {
487  return;
488  }
489 
490  MyCameraConstraint* tmp = dynamic_cast<MyCameraConstraint*>( camera()->frame()->constraint() );
491  if ( tmp != NULL ) {
492  wVector min, max;
493  world()->size( min, max );
494  setSceneBoundingBox( qglviewer::Vec( min[0], min[1], min[2] ),
495  qglviewer::Vec( max[0], max[1], max[2] ) );
496  tmp->minP = qglviewer::Vec( min[0], min[1], min[2] );
497  tmp->maxP = qglviewer::Vec( max[0], max[1], max[2] );
498  }
499 }
500 
501 void RenderWorld::wireframe( bool b ) {
502  QMutexLocker locker(&mutex);
503  wiref = b;
504 }
505 
507  QMutexLocker locker(&mutex);
508  showskygroundbox = b;
509 }
510 
511 void RenderWorld::showObjects( bool b ) {
512  QMutexLocker locker(&mutex);
513  showobjs = b;
514 }
515 
516 void RenderWorld::showJoints( bool b ) {
517  QMutexLocker locker(&mutex);
518  showjoints = b;
519 }
520 
521 void RenderWorld::showAABBs( bool b ) {
522  QMutexLocker locker(&mutex);
523  showaabbs = b;
524 }
525 
527  QMutexLocker locker(&mutex);
528  showcontacts = b;
529 }
530 
531 void RenderWorld::showForces( bool b ) {
532  QMutexLocker locker(&mutex);
533  showforces = b;
534 }
535 
537  QMutexLocker locker(&mutex);
538  showlocalaxes = b;
539 }
540 
541 void RenderWorld::showLabels( bool b ) {
542  QMutexLocker locker(&mutex);
543  showlabels = b;
544 }
545 
547  QMutexLocker locker(&mutex);
548  showtimeandstep = b;
549 }
550 
551 void RenderWorld::contextMenu( const QPoint& pos ) {
553  QList<QAction*> acts;
554  QAction* act;
555  if ( showskygroundbox ) {
556  act = new QAction( "Hide Sky-Ground", this );
557  } else {
558  act = new QAction( "Show Sky-Ground", this );
559  }
560  act->setCheckable( true );
561  act->setChecked( showskygroundbox );
562  connect( act, SIGNAL( toggled(bool) ),
563  this, SLOT( showSkyGround(bool) ) );
564  acts.append( act );
565  if ( wiref ) {
566  act = new QAction( "Hide Wireframe", this );
567  } else {
568  act = new QAction( "Show Wireframe", this );
569  }
570  act->setCheckable( true );
571  act->setChecked( wiref );
572  connect( act, SIGNAL( toggled(bool) ),
573  this, SLOT( wireframe(bool) ) );
574  acts.append( act );
575 
576  if ( showobjs ) {
577  act = new QAction( "Hide Objects", this );
578  } else {
579  act = new QAction( "Show Objects", this );
580  }
581  act->setCheckable( true );
582  act->setChecked( showobjs );
583  connect( act, SIGNAL( toggled(bool) ),
584  this, SLOT( showObjects(bool) ) );
585  acts.append( act );
586 
587  if ( showjoints ) {
588  act = new QAction( "Hide Joints", this );
589  } else {
590  act = new QAction( "Show Joints", this );
591  }
592  act->setCheckable( true );
593  act->setChecked( showjoints );
594  connect( act, SIGNAL( toggled(bool) ),
595  this, SLOT( showJoints(bool) ) );
596  acts.append( act );
597 
598  if ( showaabbs ) {
599  act = new QAction( "Hide AABBs", this );
600  } else {
601  act = new QAction( "Show AABBs", this );
602  }
603  act->setCheckable( true );
604  act->setChecked( showaabbs );
605  connect( act, SIGNAL( toggled(bool) ),
606  this, SLOT( showAABBs(bool) ) );
607  acts.append( act );
608 
609  if ( showcontacts ) {
610  act = new QAction( "Hide Contacts", this );
611  } else {
612  act = new QAction( "Show Contacts", this );
613  }
614  act->setCheckable( true );
615  act->setChecked( showcontacts );
616  connect( act, SIGNAL( toggled(bool) ),
617  this, SLOT( showContacts(bool) ) );
618  acts.append( act );
619 
620  if ( showforces ) {
621  act = new QAction( "Hide Forces", this );
622  } else {
623  act = new QAction( "Show Forces", this );
624  }
625  act->setCheckable( true );
626  act->setChecked( showforces );
627  connect( act, SIGNAL( toggled(bool) ),
628  this, SLOT( showForces(bool) ) );
629  acts.append( act );
630 
631  if ( showlocalaxes ) {
632  act = new QAction( "Hide Local Axes", this );
633  } else {
634  act = new QAction( "Show Local Axes", this );
635  }
636  act->setCheckable( true );
637  act->setChecked( showlocalaxes );
638  connect( act, SIGNAL( toggled(bool) ),
639  this, SLOT( showLocalAxes(bool) ) );
640  acts.append( act );
641 
642  if ( showlabels ) {
643  act = new QAction( "Hide Labels", this );
644  } else {
645  act = new QAction( "Show Labels", this );
646  }
647  act->setCheckable( true );
648  act->setChecked( showlabels );
649  connect( act, SIGNAL( toggled(bool) ),
650  this, SLOT( showLabels(bool) ) );
651  acts.append( act );
652 
653  QMenu::exec( acts, pos );
654 }
655 
657  // Always take the resource mutex first and then our mutex to avoid deadlocks
658  ResourcesLocker resourceLocker(this);
659  QMutexLocker locker(&mutex);
660 
661  if (world() == NULL) {
662  return;
663  }
664 
665  if ( ! stateFileName().isNull() ) {
666  if ( !restoreStateFromFile() ) {
667  }
668  }
669  wVector min, max;
670  world()->size( min, max );
671  camera()->frame()->setConstraint( new MyCameraConstraint( qglviewer::Vec( min[0], min[1], min[2] ), qglviewer::Vec( max[0], max[1], max[2] ) ) );
672  // Light0 is the default ambient light
673  glEnable(GL_LIGHT0);
674 }
675 
677  // Always take the resource mutex first and then our mutex to avoid deadlocks
678  ResourcesLocker resourceLocker(this);
679  QMutexLocker locker(&mutex);
680 
681  if (world() == NULL) {
682  return;
683  }
684 
685  if ( showskygroundbox ) {
686  glPushAttrib( GL_ALL_ATTRIB_BITS );
687  glPushMatrix();
688  drawSkyGroundBox( (QGLContext*)( QGLContext::currentContext() ) );
689  glPopMatrix();
690  glPopAttrib();
691  }
692 
693  //--- the light follow the movement of the camera
694  float pos[4] = {1.0, 0.5, 1.0, 0.0};
695  // Directionnal light
696  camera()->frame()->getPosition(pos[0], pos[1], pos[2]);
697  glLightfv( GL_LIGHT0, GL_POSITION, pos );
698 
699  //--- Display Contacts - Never in wireframe
700  if ( showcontacts ) {
701  glPushAttrib( GL_ALL_ATTRIB_BITS );
702  //--- wireframe is ignored when drawing Contacts and Joints
703  glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
704  glDisable( GL_LIGHTING );
705  // --- draws Contacts
706  contactMapIterator itera( world()->contacts() );
707  while( itera.hasNext() ) {
708  itera.next();
709  const contactVec& vec = itera.value();
710  for( int i=0; i<vec.size(); i++ ) {
711  drawSphere( vec[i].worldPos, 0.008f );
712  }
713  }
714  glPopAttrib();
715  }
716  //--- Display Joint and Kinematic chains
717  int alpha = 255;
718  if ( showjoints ) {
719  glPushAttrib( GL_ALL_ATTRIB_BITS );
720  //--- wireframe is ignored when drawing Contacts and Joints
721  glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
722  glDisable( GL_LIGHTING );
723  drawKineChains();
724  alpha = 130;
725  glPopAttrib();
726  }
727  //--- display objects
728  if ( showobjs ) {
729  glPushAttrib( GL_ALL_ATTRIB_BITS );
730  //--- wireframe only from this point to end
731  if ( wiref ) {
732  glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
733  } else {
734  glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
735  }
736  glEnable( GL_LIGHTING );
737  PhyObject* pr;
738  for( int i=0; i<graphics().size(); i++ ) {
739  RenderWObject* r = graphics()[i];
740  if ( r->object()->isInvisible() ) continue;
741  if ( showforces && ( pr=dynamic_cast<PhyObject*>(r->object()) ) ) {
742  glPushAttrib( GL_ALL_ATTRIB_BITS );
743  glColor4f( 1.0, 0.0, 0.0, 1.0 );
744  drawArrow( pr->matrix().w_pos, pr->matrix().w_pos + pr->force(), 0.1f );
745  glColor4f( 0.0, 1.0, 0.0, 1.0 );
746  drawArrow( pr->matrix().w_pos, pr->matrix().w_pos + pr->torque(), 0.1f );
747  alpha = 130;
748  glPopAttrib();
749  }
750  r->object()->setAlpha( alpha );
751  glPushAttrib( GL_ALL_ATTRIB_BITS );
752  // Checking if we have to show axes and labels of all objects
753  const bool savedShowAxesState = r->object()->localAxesDrawn();
754  const bool savedShowLabelState = r->object()->labelShown();
755  if ( showlocalaxes ) {
756  r->object()->drawLocalAxes(true);
757  }
758  if ( showlabels ) {
759  r->object()->showLabel(true);
760  }
761  r->render( (QGLContext*)( QGLContext::currentContext() ) );
762  r->object()->drawLocalAxes(savedShowAxesState);
763  r->object()->showLabel(savedShowLabelState);
764  glPopAttrib();
765  if ( showaabbs && currentSelected == i ) {
766  glPushAttrib( GL_ALL_ATTRIB_BITS );
767  r->renderAABB( this );
768  glPopAttrib();
769  wVector dims, minPoint, maxPoint;
770  r->calculateOBB( dims, minPoint, maxPoint );
771  glPushAttrib( GL_ALL_ATTRIB_BITS );
772  drawWireBox( minPoint, maxPoint, r->object()->matrix() );
773  glPopAttrib();
774  }
775  }
776  }
777 
778  //--- draw some text
779  if (showtimeandstep) {
780  glPushAttrib( GL_ALL_ATTRIB_BITS );
781  glColor4f( 1.0, 0.0, 0.0, 1.0 );
782  drawText( 80, 15, QString("time: %1 step: %2")
783  .arg(world()->elapsedTime())
784  .arg((int)(world()->elapsedTime()/world()->timeStep()))
785  );
786  glPopAttrib();
787  }
788 }
789 
791  QMutexLocker locker(&mutex);
792 
793  for( int i=0; i< graphics().size(); i++ ) {
794  glPushName(i);
795  graphics()[i]->render( (QGLContext*)( QGLContext::currentContext() ) );
796  glPopName();
797  }
798 }
799 
800 void RenderWorld::postSelection(const QPoint& point) {
801  QMutexLocker locker(&mutex);
802 
803  UNUSED_PARAM( point );
804  int i = selectedName();
805  if ( i != -1 && i != currentSelected ) {
806  graphics()[qMax(0,currentSelected)]->object()->setColor( Qt::white );
807  graphics()[i]->object()->setColor( Qt::yellow );
808  currentSelected = i;
809  }
810 }
811 
812 void RenderWorld::keyPressEvent(QKeyEvent *e) {
813  QMutexLocker locker(&mutex);
814 
815  // Get event modifiers key
816 #if QT_VERSION < 0x040000
817  // Bug in Qt : use 0x0f00 instead of Qt::KeyButtonMask with Qt versions < 3.1
818  const Qt::ButtonState modifiers = (Qt::ButtonState)(e->state() & Qt::KeyButtonMask);
819 #else
820  const Qt::KeyboardModifiers modifiers = e->modifiers();
821 #endif
822 
823  // A simple switch on e->key() is not sufficient if we want to take state key into account.
824  // With a switch, it would have been impossible to separate 'F' from 'CTRL+F'.
825  // That's why we use imbricated if...else and a "handled" boolean.
826  bool handled = false;
827  if ((e->key()==Qt::Key_Left) && (modifiers==Qt::NoButton)) {
828  // rotate camera
829  Quaternion qcur = camera()->orientation();
830  Quaternion qnew = qcur * Quaternion( Vec(0,1,0), 3.1415/30 );
831  camera()->setOrientation( qnew );
832  handled = true;
833  updateGL();
834  } else if ((e->key()==Qt::Key_Right) && (modifiers==Qt::NoButton)) {
835  // rotate camera
836  Quaternion qcur = camera()->orientation();
837  Quaternion qnew = qcur * Quaternion( Vec(0,1,0), -3.1415/30 );
838  camera()->setOrientation( qnew );
839  handled = true;
840  updateGL();
841  }
842  if ((e->key()==Qt::Key_Up) && (modifiers==Qt::NoButton)) {
843  // rotate camera
844  Quaternion qcur = camera()->orientation();
845  Quaternion qnew = qcur * Quaternion( Vec(1,0,0), 3.1415/30 );
846  camera()->setOrientation( qnew );
847  handled = true;
848  updateGL();
849  } else if ((e->key()==Qt::Key_Down) && (modifiers==Qt::NoButton)) {
850  // rotate camera
851  Quaternion qcur = camera()->orientation();
852  Quaternion qnew = qcur * Quaternion( Vec(1,0,0), -3.1415/30 );
853  camera()->setOrientation( qnew );
854  handled = true;
855  updateGL();
856  }
857  //--- Context Menu (not accessible with right-click, because right button as different meaning)
858  if ((e->key()==Qt::Key_M) && (modifiers==Qt::NoButton)) {
859  contextMenu( mapToGlobal(QPoint(10,10)) );
860  handled = true;
861  }
862 
863  if (!handled) {
865  }
866 }
867 
868 void RenderWorld::resourceChanged(QString name, ResourceChangeType changeType)
869 {
870  QMutexLocker locker(&mutex);
871 
872  // Calling parent function
873  RenderWObjectContainer::resourceChanged(name, changeType);
874 
875  if (world() == NULL) {
876  return;
877  }
878 
879  // Connecting slots and updating world dimensions
880 
881  // These connections are direct because syncronization is done with Mutexes
882  connect( world(), SIGNAL( removedObject( WObject* ) ),
883  this, SLOT( slotRemoveObject( WObject* ) ), Qt::DirectConnection );
884  connect( world(), SIGNAL( addedObject( WObject* ) ),
885  this, SLOT( slotAddObject( WObject* ) ), Qt::DirectConnection );
886  connect( world(), SIGNAL( resized() ),
887  this, SLOT( onWorldResize() ), Qt::DirectConnection );
888 
889  // !! DO NOT CONNECT TO THE advanced SIGNAL to update the renderworld becuase that signals may be
890  // emitted so fast that the GUI will freeze !!
891  //connect( world(), SIGNAL( advanced() ),
892  // this, SLOT( update() ) );
893 
894  // We can't call onWorldResize because that function tries to take a lock (and we can't from inside resourceChanged)
895  MyCameraConstraint* tmp = dynamic_cast<MyCameraConstraint*>( camera()->frame()->constraint() );
896  if ( tmp != NULL ) {
897  wVector min, max;
898  world()->size( min, max );
899  setSceneBoundingBox( qglviewer::Vec( min[0], min[1], min[2] ),
900  qglviewer::Vec( max[0], max[1], max[2] ) );
901  tmp->minP = qglviewer::Vec( min[0], min[1], min[2] );
902  tmp->maxP = qglviewer::Vec( max[0], max[1], max[2] );
903  }
904 
905  // Forcing renderworld update (we cannot call update() because here we could be in a different thread)
906  QCoreApplication::postEvent(this, new ForceRenderWorldUpdateEvent());
907 }
908 
909 void RenderWorld::drawDOF( PhyDOF* dof, bool drawAxes ) {
910  // Used inside draw(), no need to lock here
911 
912  if ( dof->joint() == NULL ) return;
913 
914  //--- FIX ME: this method handles only rotational joints :-(
915  if ( dof->translate() ) return;
916 
917  wMatrix mat;
918  mat.x_ax = dof->xAxis();
919  mat.y_ax = dof->yAxis();
920  mat.z_ax = dof->axis();
921  mat.w_pos = dof->centre();
922  mat.sanitifize();
923 
924  PhyJoint* joint = dof->joint();
925  PhyObject* child = joint->child();
926  PhyObject* parent= joint->parent();
927  RenderWorld& rw = *this;
928  wVector dims, minP, maxP;
929 // wVector lax = dof->axis();
930  rw[ child ]->calculateOBB( dims, minP, maxP );
931  real cube = (dims[0]+dims[1]+dims[2])/3.0;
932  if ( parent ) {
933  rw[ parent ]->calculateOBB( dims, minP, maxP );
934  real cube2 = (dims[0]+dims[1]+dims[2])/3.0;
935  cube = min( cube2, cube );
936  }
937  real len = cube * 0.70;
938  real rad = len * 0.25;
939 
940  mat.w_pos = dof->centre() - dof->axis().scale(len/2.0);
941  drawCylinder( mat, len, rad, QColor(Qt::cyan) );
942  if ( dof->isLimited() ) {
943  //--- draw indication about limits
944  real lo, hi;
945  dof->limits( lo, hi );
946  real ang = hi-lo;
947  mat.w_pos = wVector(0,0,0);
948  mat = mat * wMatrix( wQuaternion( dof->axis(), lo ), wVector(0,0,0) );
949  mat.w_pos = dof->centre() + dof->axis().scale(len/2.0);
950  drawTorus( rad, rad*0.6, mat, ang );
951  } else {
952  mat.w_pos = dof->centre() + dof->axis().scale(len/2.0);
953  drawTorus( rad, rad*0.6, mat );
954  }
955  //--- draw indication about current position
956  mat.x_ax = dof->xAxis();
957  mat.y_ax = dof->yAxis();
958  mat.z_ax = dof->axis();
959  mat.w_pos = wVector(0,0,0);
960  mat.sanitifize();
961  mat = mat * wMatrix( wQuaternion( dof->axis(), dof->position()-0.05 ), wVector(0,0,0) );
962  mat.w_pos = dof->centre() + dof->axis().scale(len/2.0);
963  drawTorus( rad, rad*0.55f, mat, 0.1f, Qt::green );
964 
965  if ( drawAxes ) {
966  drawArrow( dof->centre(), dof->centre()+dof->xAxis().scale(len*1.2), rad*0.4, 12, Qt::magenta );
967  drawArrow( dof->centre(), dof->centre()+dof->yAxis().scale(len*1.2), rad*0.5, 12, Qt::yellow );
968  }
969 }
970 
971 void RenderWorld::drawKineChains() {
972  // Used inside draw(), no need to lock here
973 
974  if (world() == NULL) {
975  return;
976  }
977 
978  foreach( PhyJoint* jn, world()->joints()) {
979  //if ( ! jn->isEnabled() ) continue;
980  float dist1 = 0.0f, dist2 = 0.0f;
981  wVector start = jn->centre();
982  wVector end1 = jn->child()->matrix().w_pos;
983  wVector end2 = start;
984  dist1 = wVector::distance( start, end1 );
985  if ( jn->parent() ) {
986  end2 = jn->parent()->matrix().w_pos;
987  dist2 = wVector::distance( start, end2 );
988  }
989  real rad = (dist1 + dist2) * 0.04;
990  drawCylinder( start, end1, rad*0.6 );
991  drawCylinder( start, end2, rad*0.6 );
992 
993  QVector<PhyDOF*> ds = jn->dofs();
994  for( int k=0; k<ds.size(); k++ ) {
995  drawDOF( ds[k], true );
996  }
997  }
998 }
999 
1000 void RenderWorld::customEvent(QEvent* event)
1001 {
1002  if (event->type() == QEvent::User) {
1003  // Forcing RenderWorld update
1004  update();
1005  }
1006 }
1007 
1009  GLUquadricObj *pObj;
1010 
1011  // set the color
1012  glShadeModel( GL_SMOOTH );
1013  glColor4f( 0.0f, 1.0f, 0.0f, 1.0f );
1014 
1015  wMatrix mat = wMatrix::identity();
1016  mat.w_pos = pos;
1017  mat.x_ax = mat.x_ax.scale( radius );
1018  mat.y_ax = mat.y_ax.scale( radius );
1019  mat.z_ax = mat.z_ax.scale( radius );
1020  glPushMatrix();
1021  GLMultMatrix(&mat[0][0]);
1022 
1023  // Get a new Quadric off the stack
1024  pObj = gluNewQuadric();
1025  // Get a new Quadric off the stack
1026  gluQuadricTexture(pObj, true);
1027  gluSphere(pObj, 1.0f, 20, 20);
1028 
1029  gluDeleteQuadric(pObj);
1030  glPopMatrix();
1031 }
1032 
1033 void RenderWObjectContainer::drawCylinder( wVector axis, wVector centre, float h, float rad, QColor c ) {
1034  GLUquadricObj *pObj;
1035 
1036  glPushMatrix();
1037 
1038  // set the color
1039  glShadeModel( GL_SMOOTH );
1040  glColor4f( c.redF(), c.greenF(), c.blueF(), c.alphaF() );
1041 
1042  wVector recentre = axis.scale( -h*0.5 ) + centre;
1043  glTranslatef( recentre[0], recentre[1], recentre[2] );
1044 
1045  Vec xg(0,0,1);
1046  Vec ax( axis[0], axis[1], axis[2] );
1047  Quaternion quad( xg, ax );
1048  glMultMatrixd( quad.matrix() );
1049 
1050  // Get a new Quadric off the stack
1051  pObj = gluNewQuadric();
1052  gluQuadricTexture(pObj, true);
1053  gluCylinder(pObj, rad, rad, h, 20, 2);
1054 
1055  // render the caps
1056  gluQuadricOrientation(pObj, GLU_INSIDE);
1057  gluDisk(pObj, 0.0f, rad, 20, 1);
1058 
1059  glTranslatef (0.0f, 0.0f, h);
1060  gluQuadricOrientation(pObj, GLU_OUTSIDE);
1061  gluDisk(pObj, 0.0f, rad, 20, 1);
1062 
1063  gluDeleteQuadric(pObj);
1064  glPopMatrix();
1065 }
1066 
1067 void RenderWObjectContainer::drawCylinder( wVector start, wVector end, float rad, QColor c ) {
1068  // Calling the function above to draw the cylinder
1069  const float h = (end - start).norm();
1070  const wVector axis = (end - start).scale(1.0 / h);
1071  const wVector centre = (start + end).scale(0.5);
1072 
1073  drawCylinder(axis, centre, h, rad, c);
1074 
1075 // float h = wVector::distance( start, end );
1076 // if ( h < 0.0001 ) return;
1077 //
1078 // GLUquadricObj *pObj;
1079 //
1080 // glPushMatrix();
1081 //
1082 // // set the color
1083 // glShadeModel( GL_SMOOTH );
1084 // glColor4f( c.redF(), c.greenF(), c.blueF(), c.alphaF() );
1085 //
1086 // wVector zaxis = end - start;
1087 // zaxis.normalize();
1088 // wMatrix tm = wMatrix::grammSchmidt( zaxis );
1089 // tm.w_pos = start;
1090 // GLMultMatrix( &tm[0][0] );
1091 //
1092 // // Get a new Quadric off the stack
1093 // pObj = gluNewQuadric();
1094 // gluQuadricTexture(pObj, true);
1095 // gluCylinder(pObj, rad, rad, h, 20, 2);
1096 //
1097 // // render the caps
1098 // gluQuadricOrientation(pObj, GLU_INSIDE);
1099 // gluDisk(pObj, 0.0f, rad, 20, 1);
1100 //
1101 // glTranslatef (0.0f, 0.0f, h);
1102 // gluQuadricOrientation(pObj, GLU_OUTSIDE);
1103 // gluDisk(pObj, 0.0f, rad, 20, 1);
1104 //
1105 // gluDeleteQuadric(pObj);
1106 // glPopMatrix();
1107 }
1108 
1109 void RenderWObjectContainer::drawCylinder( const wMatrix& mat, float h, float rad, QColor c ) {
1110  GLUquadricObj *pObj;
1111 
1112  glPushMatrix();
1113 
1114  // set the color
1115  glShadeModel( GL_SMOOTH );
1116  glColor4f( c.redF(), c.greenF(), c.blueF(), c.alphaF() );
1117 
1118  GLMultMatrix(&mat[0][0]);
1119 
1120  // Get a new Quadric off the stack
1121  pObj = gluNewQuadric();
1122  gluQuadricTexture(pObj, true);
1123  gluCylinder(pObj, rad, rad, h, 20, 2);
1124 
1125  // render the caps
1126  gluQuadricOrientation(pObj, GLU_INSIDE);
1127  gluDisk(pObj, 0.0f, rad, 20, 1);
1128 
1129  glTranslatef (0.0f, 0.0f, h);
1130  gluQuadricOrientation(pObj, GLU_OUTSIDE);
1131  gluDisk(pObj, 0.0f, rad, 20, 1);
1132 
1133  gluDeleteQuadric(pObj);
1134  glPopMatrix();
1135 }
1136 
1137 void RenderWObjectContainer::drawCone( const wMatrix& mat, float len, float radius, QColor c ) {
1138  GLUquadricObj *pObj;
1139 
1140  glPushMatrix();
1141 
1142  // set the color
1143  glShadeModel( GL_SMOOTH );
1144  glColor4f( c.redF(), c.greenF(), c.blueF(), c.alphaF() );
1145 
1146  GLMultMatrix(&mat[0][0]);
1147 
1148  // Get a new Quadric off the stack
1149  pObj = gluNewQuadric();
1150  gluQuadricTexture(pObj, true);
1151  gluCylinder(pObj, radius, 0, len, 20, 2);
1152 
1153  // render the caps
1154  gluQuadricOrientation(pObj, GLU_INSIDE);
1155  gluDisk(pObj, 0.0f, radius, 20, 1);
1156 
1157  gluDeleteQuadric(pObj);
1158  glPopMatrix();
1159 }
1160 
1161 void RenderWObjectContainer::drawArrow( const wVector& direction, const wVector& start, float radius, float tipRadius, float tipLength, QColor c )
1162 {
1163  // Computing some values for the arrow. The tail length is negative if the arrow has no tail, the
1164  // tip radius is scaled if the arrow has no tail
1165  const real length = direction.norm();
1166  const real tailLength = (tipLength > length) ? -1.0 : (length - tipLength);
1167  //const real effectiveTipRadius = (tipLength > length) ? (tipRadius * (length / tipLength)) : tipRadius;
1168 
1169  // Generating a transformation matrix
1170  wMatrix mtr = wMatrix::grammSchmidt(direction);
1171  mtr.w_pos = start;
1172 
1173  // First drawing the tail of the arrow (if present)
1174  if (tailLength > 0.0) {
1175  drawCylinder(mtr, tailLength, radius, c);
1176 
1177  // Translating the matrix so that it is ready for drawing the tip
1178  mtr.w_pos += mtr.z_ax.scale(tailLength);
1179  }
1180 
1181  // Drawing the tip
1182  drawCone(mtr, tipLength, tipRadius, c);
1183 }
1184 
1186  glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
1187  glPushMatrix();
1188 
1189  // set the color
1190  glShadeModel( GL_SMOOTH );
1191  glColor4f( 1.0f, 1.0f, 0.0f, 1.0f );
1192 
1193  float hdx = (dims[0]/2.0);
1194  float hdy = (dims[1]/2.0);
1195  float hdz = (dims[2]/2.0);
1196  GLMultMatrix(&matrix[0][0]);
1197 
1198  // the cube will just be drawn as six quads for the sake of simplicity
1199  // for each face, we specify the quad's normal (for lighting), then
1200  // specify the quad's 4 vertices and associated texture coordinates
1201  glBegin(GL_QUADS);
1202  // front
1203  glNormal3f(0.0, 0.0, 1.0);
1204  glVertex3f(-hdx, -hdy, hdz);
1205  glVertex3f( hdx, -hdy, hdz);
1206  glVertex3f( hdx, hdy, hdz);
1207  glVertex3f(-hdx, hdy, hdz);
1208 
1209  // back
1210  glNormal3f(0.0, 0.0, -1.0);
1211  glVertex3f( hdx, -hdy, -hdz);
1212  glVertex3f(-hdx, -hdy, -hdz);
1213  glVertex3f(-hdx, hdy, -hdz);
1214  glVertex3f( hdx, hdy, -hdz);
1215 
1216  // top
1217  glNormal3f(0.0, 1.0, 0.0);
1218  glVertex3f(-hdx, hdy, hdz);
1219  glVertex3f( hdx, hdy, hdz);
1220  glVertex3f( hdx, hdy, -hdz);
1221  glVertex3f(-hdx, hdy, -hdz);
1222 
1223  // bottom
1224  glNormal3f(0.0, -1.0, 0.0);
1225  glVertex3f(-hdx, -hdy, -hdz);
1226  glVertex3f( hdx, -hdy, -hdz);
1227  glVertex3f( hdx, -hdy, hdz);
1228  glVertex3f(-hdx, -hdy, hdz);
1229 
1230  // left
1231  glNormal3f(-1.0, 0.0, 0.0);
1232  glVertex3f(-hdx, -hdy, -hdz);
1233  glVertex3f(-hdx, -hdy, hdz);
1234  glVertex3f(-hdx, hdy, hdz);
1235  glVertex3f(-hdx, hdy, -hdz);
1236 
1237  // right
1238  glNormal3f(1.0, 0.0, 0.0);
1239  glVertex3f(hdx, -hdy, hdz);
1240  glVertex3f(hdx, -hdy, -hdz);
1241  glVertex3f(hdx, hdy, -hdz);
1242  glVertex3f(hdx, hdy, hdz);
1243  glEnd();
1244 
1245  glPopMatrix();
1246 }
1247 
1249  glPushMatrix();
1250  GLMultMatrix(&matrix[0][0]);
1251  drawWireBox( min, max );
1252  glPopMatrix();
1253 }
1254 
1256  glPolygonMode(GL_FRONT_AND_BACK, GL_LINE);
1257  glPushMatrix();
1258 
1259  // set the color
1260  glShadeModel( GL_SMOOTH );
1261  glColor4f( 1.0f, 1.0f, 0.0f, 1.0f );
1262 
1263  float dx = fabs( max[0]-min[0] );
1264  float dy = fabs( max[1]-min[1] );
1265  float dz = fabs( max[2]-min[2] );
1266  float hdx = (dx/2.0);
1267  float hdy = (dy/2.0);
1268  float hdz = (dz/2.0);
1269  float minX = qMin(min[0], max[0]);
1270  float minY = qMin(min[1], max[1]);
1271  float minZ = qMin(min[2], max[2]);
1272  glTranslatef( minX+hdx, minY+hdy, minZ+hdz );
1273 
1274  // the cube will just be drawn as six quads for the sake of simplicity
1275  // for each face, we specify the quad's normal (for lighting), then
1276  // specify the quad's 4 vertices and associated texture coordinates
1277  glBegin(GL_QUADS);
1278  // front
1279  glNormal3f(0.0, 0.0, 1.0);
1280  glVertex3f(-hdx, -hdy, hdz);
1281  glVertex3f( hdx, -hdy, hdz);
1282  glVertex3f( hdx, hdy, hdz);
1283  glVertex3f(-hdx, hdy, hdz);
1284 
1285  // back
1286  glNormal3f(0.0, 0.0, -1.0);
1287  glVertex3f( hdx, -hdy, -hdz);
1288  glVertex3f(-hdx, -hdy, -hdz);
1289  glVertex3f(-hdx, hdy, -hdz);
1290  glVertex3f( hdx, hdy, -hdz);
1291 
1292  // top
1293  glNormal3f(0.0, 1.0, 0.0);
1294  glVertex3f(-hdx, hdy, hdz);
1295  glVertex3f( hdx, hdy, hdz);
1296  glVertex3f( hdx, hdy, -hdz);
1297  glVertex3f(-hdx, hdy, -hdz);
1298 
1299  // bottom
1300  glNormal3f(0.0, -1.0, 0.0);
1301  glVertex3f(-hdx, -hdy, -hdz);
1302  glVertex3f( hdx, -hdy, -hdz);
1303  glVertex3f( hdx, -hdy, hdz);
1304  glVertex3f(-hdx, -hdy, hdz);
1305 
1306  // left
1307  glNormal3f(-1.0, 0.0, 0.0);
1308  glVertex3f(-hdx, -hdy, -hdz);
1309  glVertex3f(-hdx, -hdy, hdz);
1310  glVertex3f(-hdx, hdy, hdz);
1311  glVertex3f(-hdx, hdy, -hdz);
1312 
1313  // right
1314  glNormal3f(1.0, 0.0, 0.0);
1315  glVertex3f(hdx, -hdy, hdz);
1316  glVertex3f(hdx, -hdy, -hdz);
1317  glVertex3f(hdx, hdy, -hdz);
1318  glVertex3f(hdx, hdy, hdz);
1319  glEnd();
1320 
1321  glPopMatrix();
1322 }
1323 
1324 void RenderWObjectContainer::drawTorus( real outRad, real innRad, const wMatrix& matrix, real angle, QColor c ) {
1325  glPushMatrix();
1326 
1327  // set the color
1328  glShadeModel( GL_SMOOTH );
1329  glColor4f( c.redF(), c.greenF(), c.blueF(), c.alphaF() );
1330 
1331  GLMultMatrix(&matrix[0][0]);
1332 
1333  int numc = 8;
1334  int numt = 25;
1335  int i, j, k;
1336  double s, t, x, y, z, twopi;
1337  real tubeRad = (outRad-innRad)/2.0;
1338  real toruRad = outRad - tubeRad;
1339  twopi = 2 * PI_GRECO;
1340  for (i = 0; i < numc; i++) {
1341  glBegin(GL_QUAD_STRIP);
1342  for (j = 0; j <= numt; j++) {
1343  for (k = 1; k >= 0; k--) {
1344  s = (i + k) % numc + 0.5;
1345  t = j; //% numt;
1346 
1347  x = (toruRad+tubeRad*cos(s*twopi/numc))*cos(t*(angle)/numt);
1348  y = (toruRad+tubeRad*cos(s*twopi/numc))*sin(t*(angle)/numt);
1349  z = tubeRad * sin(s * twopi / numc);
1350  glVertex3f(x, y, z);
1351  }
1352  }
1353  glEnd();
1354  }
1355 
1356  glPopMatrix();
1357 }
1358 
1359 void RenderWObjectContainer::drawTorus( wVector axis, wVector centre, real outRad, real innRad, real angle ) {
1360  glPushMatrix();
1361 
1362  // set the color
1363  glShadeModel( GL_SMOOTH );
1364  glColor4f( 1.0f, 0.0f, 0.0f, 1.0f );
1365 
1366  wMatrix tm = wMatrix::grammSchmidt( axis );
1367  tm.w_pos = centre;
1368  GLMultMatrix( &tm[0][0] );
1369 
1370  int numc = 8;
1371  int numt = 25;
1372  int i, j, k;
1373  double s, t, x, y, z, twopi;
1374  real tubeRad = (outRad-innRad)/2.0;
1375  real toruRad = outRad - tubeRad;
1376  twopi = 2 * PI_GRECO;
1377  for (i = 0; i < numc; i++) {
1378  glBegin(GL_QUAD_STRIP);
1379  for (j = 0; j <= numt; j++) {
1380  for (k = 1; k >= 0; k--) {
1381  s = (i + k) % numc + 0.5;
1382  t = j; //% numt;
1383 
1384  x = (toruRad+tubeRad*cos(s*twopi/numc))*cos(t*(angle)/numt);
1385  y = (toruRad+tubeRad*cos(s*twopi/numc))*sin(t*(angle)/numt);
1386  z = tubeRad * sin(s * twopi / numc);
1387  glVertex3f(x, y, z);
1388  }
1389  }
1390  glEnd();
1391  }
1392 
1393  glPopMatrix();
1394 }
1395 
1396 void RenderWorld::drawArrow( const wVector& start, const wVector& end, float radius, int nbSubdivisions, QColor c ) {
1397  glPushMatrix();
1398  glColor4f( c.redF(), c.greenF(), c.blueF(), c.alphaF() );
1399 
1400  wVector zaxis = end - start;
1401  real len = zaxis.norm();
1402  zaxis.normalize();
1403  wMatrix tm = wMatrix::grammSchmidt( zaxis );
1404  tm.w_pos = start;
1405  GLMultMatrix( &tm[0][0] );
1406 
1407  QGLViewer::drawArrow( len, radius, nbSubdivisions );
1408 
1409  glPopMatrix();
1410 }
1411 
1412 } // end namespace farsa