glviewer.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include "glviewer/glviewer.h"
  17. #define GL_PI 3.1415926535897932384626433832795
  18. GLViewer::GLViewer(QWidget *parent) :
  19. QGLWidget(parent)
  20. {
  21. cameraparameters.viewAngle=60;
  22. cameraparameters.viewheight=50;
  23. cameraparameters.minView=0.001;
  24. cameraparameters.maxView=1000;
  25. cameraparameters.width=0;
  26. cameraparameters.height=0;
  27. cameraparameters.background=Eigen::Vector4d(0,0,0,1);
  28. cameraparameters.lightambient[0]=1.0;
  29. cameraparameters.lightambient[1]=1.0;
  30. cameraparameters.lightambient[2]=1.0;
  31. cameraparameters.lightambient[3]=1.0;
  32. cameraparameters.transform.setIdentity();
  33. cameraparameters.tspeed=10;
  34. cameraparameters.rspeed=1;
  35. cameraparameters.pointsize=1;
  36. bperspective=1;
  37. setMouseTracking(1);
  38. }
  39. GLViewer::~GLViewer()
  40. {
  41. makeCurrent();
  42. int i,n=displaylist.size();
  43. for(i=0;i<n;i++)
  44. {
  45. glDeleteLists(displaylist[i].listid,1);
  46. }
  47. displaylist.clear();
  48. }
  49. void GLViewer::initializeGL()
  50. {
  51. glShadeModel(GL_FLAT);
  52. glClearColor(cameraparameters.background(0),cameraparameters.background(1),cameraparameters.background(2),cameraparameters.background(3));
  53. glClearDepth(1.0);
  54. glEnable(GL_DEPTH_TEST);
  55. glDepthFunc(GL_LEQUAL);
  56. glHint(GL_PERSPECTIVE_CORRECTION_HINT, GL_NICEST);
  57. return;
  58. }
  59. void GLViewer::paintGL()
  60. {
  61. Eigen::Vector4d eye=cameraparameters.transform*Eigen::Vector4d(0,0,0,1);
  62. Eigen::Vector4d center=cameraparameters.transform*Eigen::Vector4d(0,0,-1,1);
  63. Eigen::Vector4d up=cameraparameters.transform*Eigen::Vector4d(0,1,0,0);
  64. makeCurrent();
  65. cameraparameters.eye[0]=eye(0);
  66. cameraparameters.eye[1]=eye(1);
  67. cameraparameters.eye[2]=eye(2);
  68. cameraparameters.eye[3]=eye(3);
  69. glLightfv(GL_LIGHT0, GL_POSITION,cameraparameters.eye);
  70. glLightfv(GL_LIGHT0, GL_AMBIENT, cameraparameters.lightambient);
  71. glLightfv(GL_LIGHT0, GL_DIFFUSE,cameraparameters.lightambient);
  72. glLightfv(GL_LIGHT0, GL_SPECULAR,cameraparameters.lightambient);
  73. glLightModelfv(GL_LIGHT_MODEL_AMBIENT, cameraparameters.lightambient);
  74. glLightModeli(GL_LIGHT_MODEL_LOCAL_VIEWER,GL_TRUE);
  75. glLightModeli(GL_LIGHT_MODEL_TWO_SIDE,GL_TRUE);
  76. glEnable(GL_BLEND);
  77. glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
  78. glClearColor(cameraparameters.background(0),cameraparameters.background(1),cameraparameters.background(2),0.0);
  79. glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT);
  80. glMatrixMode(GL_MODELVIEW);
  81. glLoadIdentity();
  82. gluLookAt(eye(0),eye(1),eye(2),center(0),center(1),center(2),up(0),up(1),up(2));
  83. glPushMatrix();
  84. int i,n=displaylist.size();
  85. glPointSize(cameraparameters.pointsize);
  86. for(i=0;i<n;i++)
  87. {
  88. if(displaylist[i].show)
  89. {
  90. glPushMatrix();
  91. Eigen::Matrix4d matrix=displaylist[i].scale*displaylist[i].transform;
  92. glMultMatrixd(matrix.data());
  93. glCallList(displaylist[i].listid);
  94. glPopMatrix();
  95. }
  96. }
  97. glPopMatrix();
  98. glBegin(GL_LINES);
  99. glColor4d(1,0,0,1);
  100. glVertex3d(0,0,0);glVertex3d(1,0,0);
  101. glColor4d(0,1,0,1);
  102. glVertex3d(0,0,0);glVertex3d(0,1,0);
  103. glColor4d(0,0,1,1);
  104. glVertex3d(0,0,0);glVertex3d(0,0,1);
  105. glEnd();
  106. return;
  107. }
  108. void GLViewer::setProjection()
  109. {
  110. glMatrixMode(GL_PROJECTION);
  111. glLoadIdentity();
  112. if(bperspective)
  113. {
  114. gluPerspective((GLdouble)cameraparameters.viewAngle,(GLfloat)cameraparameters.width/(GLfloat)cameraparameters.height,(GLdouble) cameraparameters.minView,(GLdouble) cameraparameters.maxView);
  115. }
  116. else
  117. {
  118. double viewheight=cameraparameters.viewheight;
  119. double viewwidth=viewheight*(double)cameraparameters.width/(double)cameraparameters.height;
  120. glOrtho((GLdouble)-viewwidth/2.0,(GLdouble)viewwidth/2.0,(GLdouble)-viewheight/2.0,(GLdouble)viewheight/2.0,cameraparameters.minView,cameraparameters.maxView);
  121. }
  122. glMatrixMode(GL_MODELVIEW);
  123. glLoadIdentity();
  124. return;
  125. }
  126. void GLViewer::resizeGL(int width, int height)
  127. {
  128. makeCurrent();
  129. if(height==0)
  130. {
  131. height=1;
  132. }
  133. cameraparameters.width=width;
  134. cameraparameters.height=height;
  135. glViewport(0,0,(GLint)cameraparameters.width,(GLint)cameraparameters.height);
  136. setProjection();
  137. return;
  138. }
  139. void GLViewer::keyPressEvent(QKeyEvent * event)
  140. {
  141. switch(event->key())
  142. {
  143. case Qt::Key_Up:
  144. {
  145. cameraparameters.transform.col(3)=cameraparameters.transform*Eigen::Vector4d(0,0,-cameraparameters.tspeed,1);
  146. }
  147. break;
  148. case Qt::Key_Down:
  149. {
  150. cameraparameters.transform.col(3)=cameraparameters.transform*Eigen::Vector4d(0,0,cameraparameters.tspeed,1);
  151. }
  152. break;
  153. case Qt::Key_Left:
  154. {
  155. cameraparameters.transform.col(3)=cameraparameters.transform*Eigen::Vector4d(-cameraparameters.tspeed,0,0,1);
  156. }
  157. break;
  158. case Qt::Key_Right:
  159. {
  160. cameraparameters.transform.col(3)=cameraparameters.transform*Eigen::Vector4d(cameraparameters.tspeed,0,0,1);
  161. }
  162. break;
  163. case Qt::Key_PageUp:
  164. {
  165. cameraparameters.transform.col(3)=cameraparameters.transform*Eigen::Vector4d(0,cameraparameters.tspeed,0,1);
  166. }
  167. break;
  168. case Qt::Key_PageDown:
  169. {
  170. cameraparameters.transform.col(3)=cameraparameters.transform*Eigen::Vector4d(0,-cameraparameters.tspeed,0,1);
  171. }
  172. break;
  173. case Qt::Key_W://w
  174. {
  175. cameraparameters.transform.block<3,3>(0,0)=cameraparameters.transform.block<3,3>(0,0)*Eigen::AngleAxisd(cameraparameters.rspeed*GL_PI/180.0,Eigen::Vector3d::UnitX());
  176. }
  177. break;
  178. case Qt::Key_S://s
  179. {
  180. cameraparameters.transform.block<3,3>(0,0)=cameraparameters.transform.block<3,3>(0,0)*Eigen::AngleAxisd(-cameraparameters.rspeed*GL_PI/180.0,Eigen::Vector3d::UnitX());
  181. }
  182. break;
  183. case Qt::Key_A://a
  184. {
  185. cameraparameters.transform.block<3,3>(0,0)=cameraparameters.transform.block<3,3>(0,0)*Eigen::AngleAxisd(cameraparameters.rspeed*GL_PI/180.0,Eigen::Vector3d::UnitY());
  186. }
  187. break;
  188. case Qt::Key_D://d
  189. {
  190. cameraparameters.transform.block<3,3>(0,0)=cameraparameters.transform.block<3,3>(0,0)*Eigen::AngleAxisd(-cameraparameters.rspeed*GL_PI/180.0,Eigen::Vector3d::UnitY());
  191. }
  192. break;
  193. case Qt::Key_Q://q
  194. {
  195. cameraparameters.transform.block<3,3>(0,0)=cameraparameters.transform.block<3,3>(0,0)*Eigen::AngleAxisd(cameraparameters.rspeed*GL_PI/180.0,Eigen::Vector3d::UnitZ());
  196. }
  197. break;
  198. case Qt::Key_E://e
  199. {
  200. cameraparameters.transform.block<3,3>(0,0)=cameraparameters.transform.block<3,3>(0,0)*Eigen::AngleAxisd(-cameraparameters.rspeed*GL_PI/180.0,Eigen::Vector3d::UnitZ());
  201. }
  202. break;
  203. case Qt::Key_Home:
  204. {
  205. cameraparameters.transform.setIdentity();
  206. }
  207. break;
  208. case Qt::Key_1:
  209. {
  210. bperspective=1;
  211. setProjection();
  212. }
  213. break;
  214. case Qt::Key_2:
  215. {
  216. bperspective=0;
  217. setProjection();
  218. }
  219. break;
  220. case Qt::Key_Equal:
  221. {
  222. if(bperspective)
  223. {
  224. cameraparameters.viewAngle+=1;
  225. }
  226. else
  227. {
  228. cameraparameters.viewheight+=1;
  229. }
  230. setProjection();
  231. }
  232. break;
  233. case Qt::Key_Minus:
  234. {
  235. if(bperspective)
  236. {
  237. cameraparameters.viewAngle-=1;
  238. }
  239. else
  240. {
  241. cameraparameters.viewheight-=1;
  242. }
  243. setProjection();
  244. }
  245. break;
  246. case Qt::Key_Period:
  247. {
  248. if(bperspective)
  249. {
  250. cameraparameters.viewAngle+=10;
  251. }
  252. else
  253. {
  254. cameraparameters.viewheight+=10;
  255. }
  256. setProjection();
  257. }
  258. break;
  259. case Qt::Key_Comma:
  260. {
  261. if(bperspective)
  262. {
  263. cameraparameters.viewAngle-=10;
  264. }
  265. else
  266. {
  267. cameraparameters.viewheight-=10;
  268. }
  269. setProjection();
  270. }
  271. break;
  272. case Qt::Key_B:
  273. {
  274. QColor color(cameraparameters.background(0)*255,cameraparameters.background(1)*255,cameraparameters.background(2)*255,cameraparameters.background(3)*255);
  275. color=QColorDialog::getColor(color,this);
  276. if(color.isValid())
  277. {
  278. cameraparameters.background(0)=color.red()/255.0;
  279. cameraparameters.background(1)=color.green()/255.0;
  280. cameraparameters.background(2)=color.blue()/255.0;
  281. cameraparameters.background(3)=color.alpha()/255.0;
  282. }
  283. }
  284. break;
  285. case Qt::Key_N:
  286. {
  287. QColor color(cameraparameters.lightambient[0]*255,cameraparameters.lightambient[1]*255,cameraparameters.lightambient[2]*255,cameraparameters.lightambient[3]*255);
  288. color=QColorDialog::getColor(color,this);
  289. if(color.isValid())
  290. {
  291. cameraparameters.lightambient[0]=color.red()/255.0;
  292. cameraparameters.lightambient[1]=color.green()/255.0;
  293. cameraparameters.lightambient[2]=color.blue()/255.0;
  294. cameraparameters.lightambient[3]=color.alpha()/255.0;
  295. }
  296. }
  297. break;
  298. case Qt::Key_O:
  299. {
  300. cameraparameters.pointsize--;
  301. if(cameraparameters.pointsize<1)
  302. {
  303. cameraparameters.pointsize=1;
  304. }
  305. }
  306. break;
  307. case Qt::Key_P:
  308. {
  309. cameraparameters.pointsize++;
  310. }
  311. break;
  312. case Qt::Key_Delete:
  313. {
  314. int i,n=displaylist.size();
  315. this->makeCurrent();
  316. for(i=0;i<n;i++)
  317. {
  318. glNewList(displaylist[i].listid,GL_COMPILE);
  319. glEndList();
  320. }
  321. this->update();
  322. }
  323. break;
  324. }
  325. update();
  326. return;
  327. }
  328. void GLViewer::mousePressEvent(QMouseEvent *event)
  329. {
  330. setFocus();
  331. emit mousePositionSignal(event,&cameraparameters);
  332. return;
  333. }
  334. void GLViewer::mouseReleaseEvent(QMouseEvent *event)
  335. {
  336. emit mousePositionSignal(event,&cameraparameters);
  337. return;
  338. }
  339. void GLViewer::wheelEvent(QWheelEvent * event)
  340. {
  341. int numdegrees=event->delta()/8;
  342. int numsteps=numdegrees/15;
  343. cameraparameters.tspeed*=pow(2.0,(double)numsteps);
  344. if(cameraparameters.tspeed>10)
  345. {
  346. cameraparameters.tspeed=10;
  347. }
  348. else if(cameraparameters.tspeed<0.01)
  349. {
  350. cameraparameters.tspeed=0.01;
  351. }
  352. }
  353. void GLViewer::mouseMoveEvent(QMouseEvent *event)
  354. {
  355. emit mousePositionSignal(event,&cameraparameters);
  356. return;
  357. }
  358. void GLViewer::addDisplayList(GLuint listid)
  359. {
  360. if(listid==0)
  361. {
  362. return;
  363. }
  364. else
  365. {
  366. DISPLAYLIST templist;
  367. templist.listid=listid;
  368. templist.show=1;
  369. templist.transform.setIdentity();
  370. templist.scale.setIdentity();
  371. displaylist.push_back(templist);
  372. }
  373. return;
  374. }
  375. void GLViewer::addDisplayLists(GLuint listid, GLuint num)
  376. {
  377. makeCurrent();
  378. int i,n=num;
  379. for(i=0;i<n;i++)
  380. {
  381. DISPLAYLIST list;
  382. list.listid=listid+i;
  383. list.show=1;
  384. displaylist.push_back(list);
  385. }
  386. return;
  387. }
  388. void GLViewer::enableShow(GLuint listid, bool show, bool islistid)
  389. {
  390. if(islistid)
  391. {
  392. int i;
  393. int n=displaylist.size();
  394. for(i=0;i<n;i++)
  395. {
  396. if(displaylist[i].listid==listid)
  397. {
  398. displaylist[i].show=show;
  399. break;
  400. }
  401. }
  402. }
  403. else
  404. {
  405. displaylist[listid].show=show;
  406. }
  407. return;
  408. }
  409. void GLViewer::deleteDisplayList(GLuint listid, bool islistid)
  410. {
  411. if(islistid)
  412. {
  413. int i;
  414. int n=displaylist.size();
  415. for(i=0;i<n;i++)
  416. {
  417. if(displaylist[i].listid==listid)
  418. {
  419. displaylist.erase(displaylist.begin()+i);
  420. break;
  421. }
  422. }
  423. }
  424. else
  425. {
  426. displaylist.erase(displaylist.begin()+listid);
  427. }
  428. return;
  429. }
  430. void GLViewer::clearDisplayList()
  431. {
  432. displaylist.clear();
  433. return;
  434. }
  435. int GLViewer::listSize()
  436. {
  437. return displaylist.size();
  438. }
  439. void GLViewer::setCameraPose(Eigen::Matrix4d transform)
  440. {
  441. transform.block<3,3>(0,0).normalize();
  442. cameraparameters.transform=transform;
  443. return;
  444. }
  445. Eigen::Matrix4d GLViewer::getCameraPose()
  446. {
  447. return cameraparameters.transform;
  448. }
  449. void GLViewer::setBackground(QColor color)
  450. {
  451. cameraparameters.background(0)=color.red()/255.0;
  452. cameraparameters.background(1)=color.green()/255.0;
  453. cameraparameters.background(2)=color.blue()/255.0;
  454. cameraparameters.background(3)=color.alpha()/255.0;
  455. return;
  456. }
  457. void GLViewer::setDisplayListScale(GLuint listid, double sx, double sy, double sz, bool islistid)
  458. {
  459. if(islistid)
  460. {
  461. int i;
  462. int n=displaylist.size();
  463. for(i=0;i<n;i++)
  464. {
  465. if(displaylist[i].listid==listid)
  466. {
  467. displaylist[i].scale(0,0)=sx;
  468. displaylist[i].scale(1,1)=sy;
  469. displaylist[i].scale(2,2)=sz;
  470. break;
  471. }
  472. }
  473. }
  474. else
  475. {
  476. displaylist[listid].scale(0,0)=sx;
  477. displaylist[listid].scale(1,1)=sy;
  478. displaylist[listid].scale(2,2)=sz;
  479. }
  480. return;
  481. }
  482. void GLViewer::setDisplayListRotation(GLuint listid, double rx, double ry, double rz, bool islistid)
  483. {
  484. if(islistid)
  485. {
  486. int i;
  487. int n=displaylist.size();
  488. for(i=0;i<n;i++)
  489. {
  490. if(displaylist[i].listid==listid)
  491. {
  492. Eigen::Matrix3d rotation;
  493. rotation=Eigen::AngleAxisd(rz,Eigen::Vector3d::UnitZ())*Eigen::AngleAxisd(ry,Eigen::Vector3d::UnitY())*Eigen::AngleAxisd(rx,Eigen::Vector3d::UnitX());
  494. displaylist[i].transform.block<3,3>(0,0)=rotation;
  495. break;
  496. }
  497. }
  498. }
  499. else
  500. {
  501. Eigen::Matrix3d rotation;
  502. rotation=Eigen::AngleAxisd(rz,Eigen::Vector3d::UnitZ())*Eigen::AngleAxisd(ry,Eigen::Vector3d::UnitY())*Eigen::AngleAxisd(rx,Eigen::Vector3d::UnitX());
  503. displaylist[listid].transform.block<3,3>(0,0)=rotation;
  504. }
  505. return;
  506. }
  507. void GLViewer::setDisplayListTranslation(GLuint listid, double tx, double ty, double tz, bool islistid)
  508. {
  509. if(islistid)
  510. {
  511. int i;
  512. int n=displaylist.size();
  513. for(i=0;i<n;i++)
  514. {
  515. if(displaylist[i].listid==listid)
  516. {
  517. displaylist[i].transform(0,3)=tx;
  518. displaylist[i].transform(1,3)=ty;
  519. displaylist[i].transform(2,3)=tz;
  520. break;
  521. }
  522. }
  523. }
  524. else
  525. {
  526. displaylist[listid].transform(0,3)=tx;
  527. displaylist[listid].transform(1,3)=ty;
  528. displaylist[listid].transform(2,3)=tz;
  529. }
  530. return;
  531. }
  532. void GLViewer::setDisplayListTransform(GLuint listid, Eigen::Matrix4d transform, bool islistid)
  533. {
  534. if(islistid)
  535. {
  536. int i;
  537. int n=displaylist.size();
  538. for(i=0;i<n;i++)
  539. {
  540. if(displaylist[i].listid==listid)
  541. {
  542. displaylist[i].transform=transform;
  543. break;
  544. }
  545. }
  546. }
  547. else
  548. {
  549. displaylist[listid].transform=transform;
  550. }
  551. return;
  552. }