MRPT  2.0.1
test.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
11 #include <mrpt/maps/COctoMap.h>
13 #include <mrpt/opengl.h>
15 #include <mrpt/random.h>
16 #include <mrpt/system/filesystem.h>
17 #include <iostream>
18 
19 using namespace std;
20 using namespace mrpt;
21 using namespace mrpt::gui;
22 using namespace mrpt::opengl;
23 using namespace mrpt::math;
24 using namespace std::string_literals;
25 
26 // ------------------------------------------------------
27 // TestOpenGLObjects
28 // ------------------------------------------------------
29 void TestOpenGLObjects()
30 {
32 
33  CDisplayWindow3D win("Demo of MRPT's OpenGL objects", 640, 480);
34 
35  COpenGLScene::Ptr& theScene = win.get3DSceneAndLock();
36 
38 
39  // Lights:
41  theScene->getViewport()->lightParameters();
42  lights.direction = mrpt::math::TVector3Df(-1, -1, -1).unitarize();
43 
44  // Objects:
45  double off_x = 0;
46  const double off_y_label = 20;
47  const double STEP_X = 25;
48 
49  // XY Grid
50  /**
51  * Define each one of the objects in its own scope and just attach it to the
52  * scene by using insert(obj) method call.
53  */
54  {
55  // using mrpt smart pointers so that obj survives outside this scope.
56  auto obj = opengl::CGridPlaneXY::Create(-7, 7, -7, 7, 0, 1);
57  obj->setColor(0.7f, 0.7f, 0.7f);
58  obj->setLocation(off_x, 0, 0);
59  theScene->insert(obj);
60 
61  auto obj2 = opengl::CGridPlaneXY::Create(-9, 9, -9, 9, 0, 2);
62  obj2->setColor(0.3f, 0.3f, 0.3f, 0.99f);
63  obj2->setLocation(off_x, 20, 0);
64  obj2->enableAntiAliasing();
65  theScene->insert(obj2);
66 
67  auto gl_txt = opengl::CText::Create("CGridPlaneXY");
68  gl_txt->setLocation(off_x, off_y_label, 0);
69  theScene->insert(gl_txt);
70  }
71  off_x += STEP_X;
72 
73  // XZ Grid
74  {
75  auto obj = opengl::CGridPlaneXZ::Create(-7, 7, -7, 7, 0, 1);
76  obj->setColor(0.7f, 0.7f, 0.7f);
77  obj->setLocation(off_x, 0, 0);
78  theScene->insert(obj);
79 
80  auto gl_txt = opengl::CText::Create("CGridPlaneXZ");
81  gl_txt->setLocation(off_x, off_y_label, 0);
82  theScene->insert(gl_txt);
83  }
84  off_x += STEP_X;
85 
86  // Arrow
87  {
88  auto obj = opengl::CArrow::Create(0, 0, 0, 3, 0, 0, 0.2f, 0.1f, 0.2f);
89  obj->setLocation(off_x, 0, 0);
90  obj->setColor(1, 0, 0);
91  obj->setName("arrow #1");
92  obj->enableShowName();
93  theScene->insert(obj);
94 
95  auto obj2 = opengl::CArrow::Create(1, 2, 3, 6, -3, 0, 0.1f, 0.1f, 0.3f);
96  obj2->setLocation(off_x, 0, 0);
97  obj2->setColor(0, 0, 1);
98  theScene->insert(obj2);
99 
100  auto gl_txt = opengl::CText::Create("CArrow");
101  gl_txt->setLocation(off_x, off_y_label, 0);
102  theScene->insert(gl_txt);
103  }
104  off_x += STEP_X;
105 
106  // Axis
107  {
108  auto obj = opengl::CAxis::Create(-6, -6, -6, 6, 6, 6, 2, 2, true);
109  obj->setLocation(off_x, 0, 0);
110  theScene->insert(obj);
111 
112  auto gl_txt = opengl::CText::Create("CAxis");
113  gl_txt->setLocation(off_x, off_y_label, 0);
114  theScene->insert(gl_txt);
115  }
116  off_x += STEP_X;
117 
118  // Box
119  {
120  auto obj = opengl::CBox::Create(
121  TPoint3D(0, 0, 0), TPoint3D(1, 1, 1), true, 3.0);
122  obj->setLocation(off_x, 0, 0);
123  theScene->insert(obj);
124 
125  auto obj2 =
126  opengl::CBox::Create(TPoint3D(0, 0, 0), TPoint3D(1, 1, 1), false);
127  obj2->setLocation(off_x, 4, 0);
128  theScene->insert(obj2);
129 
130  auto obj3 =
131  opengl::CBox::Create(TPoint3D(0, 0, 0), TPoint3D(1, 1, 1), false);
132  obj3->enableBoxBorder(true);
133  obj3->setLineWidth(3);
134  obj3->setColor_u8(0xff, 0x00, 0x00, 0xa0);
135  obj3->setLocation(off_x, 8, 0);
136  theScene->insert(obj3);
137 
138  auto gl_txt = opengl::CText::Create("CBox");
139  gl_txt->setLocation(off_x, off_y_label, 0);
140  theScene->insert(gl_txt);
141  }
142  off_x += STEP_X;
143 
144  // Frustum
145  {
146  auto obj = opengl::CFrustum::Create(1, 5, 60, 45, 1.5f, true, false);
147  obj->setLocation(off_x, 0, 0);
148  theScene->insert(obj);
149 
150  auto obj2 = opengl::CFrustum::Create(1, 5, 60, 45, 2.5f, true, true);
151  obj2->setLocation(off_x, 6, 0);
152  obj2->setColor_u8(0xff, 0x00, 0x00, 0x80);
153  theScene->insert(obj2);
154 
155  auto gl_txt = opengl::CText::Create("CFrustum");
156  gl_txt->setLocation(off_x, off_y_label, 0);
157  theScene->insert(gl_txt);
158  }
159  off_x += STEP_X;
160 
161  // Cylinder
162  {
163  auto obj = opengl::CCylinder::Create(2, 2, 4, 20);
164  obj->setLocation(off_x, 0, 0);
165  obj->setColor(0, 0, 0.8f);
166  theScene->insert(obj);
167 
168  auto obj2 = opengl::CCylinder::Create(2, 1, 4, 20);
169  obj2->setLocation(off_x, 6, 0);
170  obj2->setColor(0, 0, 0.8f);
171  theScene->insert(obj2);
172 
173  auto obj3 = opengl::CCylinder::Create(2, 0, 4, 20);
174  obj3->setLocation(off_x, -6, 0);
175  obj3->setColor(0, 0, 0.8f);
176  theScene->insert(obj3);
177 
178  auto gl_txt = opengl::CText::Create("CCylinder");
179  gl_txt->setLocation(off_x, off_y_label, 0);
180  theScene->insert(gl_txt);
181  }
182  off_x += STEP_X;
183 
184  // CDisk
185  {
186  {
187  auto obj = opengl::CDisk::Create(2.0f, 1.8f, 50);
188  obj->setLocation(off_x, 0, 0);
189  obj->setColor(0.8f, 0, 0);
190  theScene->insert(obj);
191  }
192 
193  {
194  auto obj = opengl::CDisk::Create(2.0f, 0, 50);
195  obj->setLocation(off_x, 5, 0);
196  obj->setColor(0.8f, 0, 0);
197  theScene->insert(obj);
198  }
199 
200  auto gl_txt = opengl::CText::Create("CDisk");
201  gl_txt->setLocation(off_x, off_y_label, 0);
202  theScene->insert(gl_txt);
203  }
204  off_x += STEP_X;
205 
206  // CEllipsoid3D
207  {
208  const double cov3d_dat[] = {0.9, 0.7, -0.4, 0.7, 1.6,
209  -0.6, -0.4, -0.6, 1.5};
210  const double cov2d_dat[] = {0.9, 0.7, 0.7, 1.6};
211  mrpt::math::CMatrixDouble22 cov2d(cov2d_dat);
212  mrpt::math::CMatrixDouble33 cov3d(cov3d_dat);
213 
214  {
215  auto obj = opengl::CEllipsoid2D::Create();
216  obj->setCovMatrix(cov2d);
217  obj->setLocation(off_x, 6, 0);
218  obj->setQuantiles(2.0);
219  theScene->insert(obj);
220  }
221  {
222  auto obj = opengl::CEllipsoid2D::Create();
223  obj->setCovMatrix(cov2d);
224  obj->setLocation(off_x, 12, 0);
225  obj->enableDrawSolid3D(true);
226  obj->setQuantiles(2.0);
227  theScene->insert(obj);
228  }
229  {
230  auto obj = opengl::CEllipsoid3D::Create();
231  obj->setCovMatrix(cov3d);
232  obj->setQuantiles(2.0);
233  obj->enableDrawSolid3D(false);
234  obj->setLocation(off_x, 0, 0);
235  theScene->insert(obj);
236  }
237  {
238  auto obj = opengl::CEllipsoid3D::Create();
239  obj->setCovMatrix(cov3d);
240  obj->setQuantiles(2.0);
241  obj->enableDrawSolid3D(true);
242  obj->setLocation(off_x, -6, 0);
243  theScene->insert(obj);
244  }
245 
246  auto gl_txt = opengl::CText::Create("CEllipsoid3D");
247  gl_txt->setLocation(off_x, off_y_label, 0);
248  theScene->insert(gl_txt);
249  }
250  off_x += STEP_X;
251 
252  // CEllipsoidRangeBearing2D
253  { // (range,bearing) -> (x,y)
254  const double cov_params_dat[] = {0.2, 0, 0, 0.1};
255  const double mean_params_dat[] = {3.0, 0.5};
256  mrpt::math::CMatrixFixed<double, 2, 2> cov_params(cov_params_dat);
257  mrpt::math::CMatrixFixed<double, 2, 1> mean_params(mean_params_dat);
258 
259  {
260  auto obj = opengl::CEllipsoidRangeBearing2D::Create();
261  obj->setCovMatrixAndMean(cov_params, mean_params);
262  obj->setLocation(off_x, 6, 0);
263  obj->setQuantiles(2.0f);
264  // obj->setNumberOfSegments(50);
265  theScene->insert(obj);
266 
267  auto obj_corner = opengl::stock_objects::CornerXYSimple(1, 3);
268  obj_corner->setLocation(off_x, 6, 0);
269  theScene->insert(obj_corner);
270  }
271  }
272  { // (range,bearing) -> (x,y)
273  const double cov_params_dat[] = {0.2, 0.09, 0.09, 0.1};
274  const double mean_params_dat[] = {5.0, -0.5};
275  mrpt::math::CMatrixFixed<double, 2, 2> cov_params(cov_params_dat);
276  mrpt::math::CMatrixFixed<double, 2, 1> mean_params(mean_params_dat);
277 
278  {
279  auto obj = opengl::CEllipsoidRangeBearing2D::Create();
280  obj->setCovMatrixAndMean(cov_params, mean_params);
281  obj->setLocation(off_x, 0, 0);
282  obj->setQuantiles(2.0f);
283  // obj->setNumberOfSegments(50);
284  theScene->insert(obj);
285 
286  auto obj_corner = opengl::stock_objects::CornerXYSimple(1, 3);
287  obj_corner->setLocation(off_x, 0, 0);
288  theScene->insert(obj_corner);
289  }
290 
291  auto gl_txt = opengl::CText::Create("CEllipsoidRangeBearing2D");
292  gl_txt->setLocation(off_x, off_y_label, 0);
293  theScene->insert(gl_txt);
294  }
295  off_x += STEP_X;
296 
297  // CEllipsoidInverseDepth2D
298  { // (inv_range,yaw) -> (x,y)
299  // Formula from our book (ch8) for confidence intervals of 3sigmas:
300  const double max_dist = 1e4;
301  const double min_dist = 1;
302  const double rho_mean = 0.5 * (1. / min_dist + 1. / max_dist);
303  const double rho_std = (1. / 6.) * (1. / min_dist - 1. / max_dist);
304 
305  const double cov_params_dat[] = {square(rho_std), 0, 0,
306  square(2.0_deg)};
307  const double mean_params_dat[] = {rho_mean, 70.0_deg};
308  mrpt::math::CMatrixFixed<double, 2, 2> cov_params(cov_params_dat);
309  mrpt::math::CMatrixFixed<double, 2, 1> mean_params(mean_params_dat);
310 
311  {
312  auto obj = opengl::CEllipsoidInverseDepth2D::Create();
313  obj->setCovMatrixAndMean(cov_params, mean_params);
314  obj->setLocation(off_x, 6, 0);
315  obj->setQuantiles(3.f);
316  obj->setNumberOfSegments(100);
317  theScene->insert(obj);
318 
319  auto obj_corner = opengl::stock_objects::CornerXYSimple(1, 3);
320  obj_corner->setLocation(off_x, 6, 0);
321  theScene->insert(obj_corner);
322  }
323 
324  auto gl_txt = opengl::CText::Create("CEllipsoidInverseDepth2D");
325  gl_txt->setLocation(off_x, off_y_label, 0);
326  theScene->insert(gl_txt);
327  }
328  off_x += STEP_X;
329 
330  // CEllipsoidInverseDepth3D
331  { // (inv_range,yaw,pitch) -> (x,y,z)
332  // Formula from our book (ch8) for confidence intervals of 3sigmas:
333  const double max_dist = 1e2;
334  const double min_dist = 1;
335  const double rho_mean = 0.5 * (1. / min_dist + 1. / max_dist);
336  const double rho_std = (1. / 6.) * (1. / min_dist - 1. / max_dist);
337 
338  const double cov_params_dat[] = {square(rho_std), 0, 0, 0,
339  square(2.0_deg), 0, 0, 0,
340  square(2.0_deg)};
341  const double mean_params_dat[] = {rho_mean, 30.0_deg, -45.0_deg};
342  mrpt::math::CMatrixFixed<double, 3, 3> cov_params(cov_params_dat);
343  mrpt::math::CMatrixFixed<double, 3, 1> mean_params(mean_params_dat);
344 
345  {
346  auto obj = opengl::CEllipsoidInverseDepth3D::Create();
347  obj->setCovMatrixAndMean(cov_params, mean_params);
348  obj->setLocation(off_x, 0, 0);
349  obj->setQuantiles(3.f);
350  // obj->setNumberOfSegments(50);
351  theScene->insert(obj);
352 
353  auto obj_corner = opengl::stock_objects::CornerXYZSimple(1, 3);
354  obj_corner->setLocation(off_x, 0, 0);
355  theScene->insert(obj_corner);
356  }
357 
358  auto gl_txt = opengl::CText::Create("CEllipsoidInverseDepth3D");
359  gl_txt->setLocation(off_x, off_y_label, 0);
360  theScene->insert(gl_txt);
361  }
362  off_x += STEP_X;
363 
364  // CMesh3D
365  {
366  auto obj = opengl::CMesh3D::Create();
367  obj->enableShowEdges(false);
368  obj->enableShowFaces(true);
369  obj->enableShowVertices(false);
370  obj->setLocation(off_x, 0, 0);
371 
372  const unsigned int rows = 200, cols = 200;
373  const unsigned int num_verts = (rows + 1) * (cols + 1);
374  const unsigned int num_faces = rows * cols;
375  int* vert_per_face = new int[num_faces];
376  int* face_verts = new int[4 * num_faces];
377  float* vert_coords = new float[3 * num_verts];
378 
379  // Assign vertices to faces and set them to be Quads
380  unsigned int first_ind = 0;
381  for (unsigned int u = 0; u < cols; u++)
382  {
383  for (unsigned int v = 0; v < rows; v++)
384  {
385  const unsigned int face_ind = v + u * rows;
386  vert_per_face[face_ind] = 4;
387 
388  face_verts[4 * face_ind] = first_ind;
389  face_verts[4 * face_ind + 1] = first_ind + 1;
390  face_verts[4 * face_ind + 2] = first_ind + rows + 2;
391  face_verts[4 * face_ind + 3] = first_ind + rows + 1;
392  first_ind++;
393  }
394 
395  first_ind++;
396  }
397 
398  // Create vert coords
399  for (unsigned int u = 0; u <= cols; u++)
400  for (unsigned int v = 0; v <= rows; v++)
401  {
402  const unsigned int vert_ind = v + u * (rows + 1);
403 
404  vert_coords[3 * vert_ind] = (2.f - 0.01f * u) *
405  (2.f + cos(0.01f * M_PI * v)) *
406  cos(0.01f * M_PI * u);
407  vert_coords[3 * vert_ind + 1] = (2.f - 0.01f * u) *
408  (2.f + cos(0.01f * M_PI * v)) *
409  sin(0.01f * M_PI * u);
410  vert_coords[3 * vert_ind + 2] =
411  3.f * 0.01f * u + (2.f - 0.01f * u) * sin(0.01f * M_PI * v);
412  }
413 
414  obj->loadMesh(
415  num_verts, num_faces, vert_per_face, face_verts, vert_coords);
416  theScene->insert(obj);
417 
418  auto gl_txt = opengl::CText::Create("CMesh3D");
419  gl_txt->setLocation(off_x, off_y_label, 0);
420  theScene->insert(gl_txt);
421  }
422  off_x += STEP_X;
423 
424  // CMeshFast, CMesh:
425  {
426  opengl::CMeshFast::Ptr obj1 = opengl::CMeshFast::Create();
427  opengl::CMeshFast::Ptr obj2 = opengl::CMeshFast::Create();
428  opengl::CMesh::Ptr obj3 = opengl::CMesh::Create();
429  opengl::CMesh::Ptr obj4 = opengl::CMesh::Create();
430 
431  obj1->setXBounds(-1, 1);
432  obj1->setYBounds(-1, 1);
433 
434  const int W = 128, H = 128;
435 
437 
438  for (int r = 0; r < H; r++)
439  for (int c = 0; c < W; c++)
440  Z(r, c) = sin(0.05 * (c + r) - 0.5) * cos(0.9 - 0.03 * r);
441 
442  const std::string texture_file = mrpt::system::getShareMRPTDir() +
443  "datasets/sample-texture-terrain.jpg"s;
444 
446 
447  // obj1:
448  obj1->setZ(Z);
449  obj1->enableColorFromZ(true);
450  obj1->setPointSize(2.0);
451  obj1->setLocation(off_x, 0, 0);
452  theScene->insert(obj1);
453 
454  // obj 2:
455  if (im.loadFromFile(texture_file))
456  {
457  obj2->assignImageAndZ(im, Z);
458  obj2->setPointSize(2.0);
459  obj2->setLocation(off_x, 3, 0);
460  theScene->insert(obj2);
461  }
462  {
463  auto gl_txt = opengl::CText::Create("CMeshFast");
464  gl_txt->setLocation(off_x, off_y_label, 0);
465  theScene->insert(gl_txt);
466  }
467 
468  off_x += STEP_X;
469 
470  // obj 3:
471  obj3->setZ(Z);
472  obj3->enableColorFromZ(true, mrpt::img::cmJET);
473  obj3->enableWireFrame(true);
474  obj3->setLocation(off_x, 0, 0);
475  theScene->insert(obj3);
476 
477  // obj 4:
478  if (im.getWidth() > 1)
479  {
480  obj4->assignImageAndZ(im, Z);
481  obj4->setLocation(off_x, 3, 0);
482  theScene->insert(obj4);
483  }
484 
485  {
486  auto gl_txt = opengl::CText::Create("CMesh");
487  gl_txt->setLocation(off_x, off_y_label, 0);
488  theScene->insert(gl_txt);
489  }
490  }
491  off_x += STEP_X;
492 
493  // CPointCloud
494  {
495  auto obj = opengl::CPointCloud::Create();
496  obj->setLocation(off_x, 0, 0);
497  theScene->insert(obj);
498 
499  obj->setPointSize(1.0);
500  obj->enableColorFromY();
501 
502  for (int i = 0; i < 100000; i++)
503  obj->insertPoint(
504  rng.drawUniform<float>(-5, 5), rng.drawUniform<float>(-5, 5),
505  rng.drawUniform<float>(-5, 5));
506 
507  auto gl_txt = opengl::CText::Create("CPointCloud");
508  gl_txt->setLocation(off_x, off_y_label, 0);
509  theScene->insert(gl_txt);
510  }
511  off_x += STEP_X;
512 
513  // CPointCloudColoured
514  {
515  auto obj = opengl::CPointCloudColoured::Create();
516  obj->setLocation(off_x, 0, 0);
517  theScene->insert(obj);
518 
519  obj->setPointSize(1.0);
520 
521  for (int i = 0; i < 200; i++)
522  obj->push_back(
523  rng.drawUniform<float>(-5, 5), rng.drawUniform<float>(-5, 5),
524  rng.drawUniform<float>(-5, 5), rng.drawUniform<float>(0, 1),
525  rng.drawUniform<float>(0, 1), rng.drawUniform<float>(0, 1));
526 
527  auto gl_txt = opengl::CText::Create("CPointCloudColoured");
528  gl_txt->setLocation(off_x, off_y_label, 0);
529  theScene->insert(gl_txt);
530  }
531  off_x += STEP_X;
532 
533  // CPolyhedron
534  {
535  {
536  auto obj = opengl::CPolyhedron::CreateCuboctahedron(1.0);
537  obj->setLocation(off_x, 0, 0);
538  obj->setWireframe(true);
539  theScene->insert(obj);
540  }
541  {
542  auto obj = opengl::CPolyhedron::CreateDodecahedron(1.0);
543  obj->setLocation(off_x, -5, 0);
544  theScene->insert(obj);
545  }
546  {
547  auto obj = opengl::CPolyhedron::CreateIcosahedron(1.0);
548  obj->setLocation(off_x, 5, 0);
549  theScene->insert(obj);
550  }
551 
552  auto gl_txt = opengl::CText::Create("CPolyhedron");
553  gl_txt->setLocation(off_x, off_y_label, 0);
554  theScene->insert(gl_txt);
555  }
556  off_x += STEP_X;
557 
558  // CSphere
559  {
560  {
561  auto obj = opengl::CSphere::Create(3.0);
562  obj->setLocation(off_x, 0, 0);
563  theScene->insert(obj);
564  }
565 
566  auto gl_txt = opengl::CText::Create("CSphere");
567  gl_txt->setLocation(off_x, off_y_label, 0);
568  theScene->insert(gl_txt);
569  }
570  off_x += STEP_X;
571 
572  // CText
573  {
574  {
575  auto obj = opengl::CText::Create(
576  "This is a CText example! My size is invariant to "
577  "eye-distance");
578  obj->setLocation(off_x, 0, 0);
579  theScene->insert(obj);
580  }
581 
582  auto gl_txt = opengl::CText::Create("CText");
583  gl_txt->setLocation(off_x, off_y_label, 0);
584  theScene->insert(gl_txt);
585  }
586  off_x += STEP_X;
587 
588  // CText3D
589  {
590  {
591  auto obj = opengl::CText3D::Create("I'm a cool CText3D!");
592  obj->setLocation(off_x, 0, 0);
593  theScene->insert(obj);
594  }
595 
596  {
597  auto obj = opengl::CText3D::Create("A rotated CText3D");
598  obj->setPose(
599  mrpt::poses::CPose3D(off_x, 0, 0, 0, 0, 0) +
600  mrpt::poses::CPose3D::FromString("[0 5 0 180 0 90]"));
601  theScene->insert(obj);
602  }
603 
604  auto gl_txt = opengl::CText::Create("CText3D");
605  gl_txt->setLocation(off_x, off_y_label, 0);
606  theScene->insert(gl_txt);
607  }
608  off_x += STEP_X;
609 
610  // CColorMap
611  {
612  {
613  auto obj = opengl::CColorBar::Create(
614  mrpt::img::cmHOT, 0.2, 1.0, 0.0, 1.0, -50.0, 100.0,
615  "%7.02f m/s");
616  obj->setLocation(off_x, 0, 0);
617  theScene->insert(obj);
618  }
619 
620  auto gl_txt = opengl::CText::Create("CColorBar");
621  gl_txt->setLocation(off_x, off_y_label, 0);
622  theScene->insert(gl_txt);
623  }
624  off_x += STEP_X;
625 
626  // CSetOfLines
627  {
628  for (int rep = 0; rep < 2; rep++)
629  {
630  auto obj = opengl::CSetOfLines::Create();
631  obj->setLocation(off_x, rep * 20, 0);
632 
633  for (int i = 0; i < 15; i++)
634  obj->appendLine(
635  rng.drawUniform(-5, 5), rng.drawUniform(-5, 5),
636  rng.drawUniform(-5, 5), rng.drawUniform(-5, 5),
637  rng.drawUniform(-5, 5), rng.drawUniform(-5, 5));
638 
639  if (rep == 1) obj->setVerticesPointSize(5.0f);
640  theScene->insert(obj);
641  }
642 
643  auto gl_txt = opengl::CText::Create("CSetOfLines");
644  gl_txt->setLocation(off_x, off_y_label, 0);
645  theScene->insert(gl_txt);
646  }
647  off_x += STEP_X;
648 
649  // CSimpleLine
650  {
651  {
652  auto obj = opengl::CSimpleLine::Create();
653  obj->setLocation(off_x, 0, 0);
654 
655  obj->setLineCoords(
656  rng.drawUniform<float>(-5, 5), rng.drawUniform<float>(-5, 5),
657  rng.drawUniform<float>(-5, 5), rng.drawUniform<float>(-5, 5),
658  rng.drawUniform<float>(-5, 5), rng.drawUniform<float>(-5, 5));
659 
660  theScene->insert(obj);
661  }
662 
663  auto gl_txt = opengl::CText::Create("CSimpleLine");
664  gl_txt->setLocation(off_x, off_y_label, 0);
665  theScene->insert(gl_txt);
666  }
667  off_x += STEP_X;
668 
669  // CVectorField2D
670  {
671  {
672  auto obj = opengl::CVectorField2D::Create();
673  obj->setLocation(off_x, 0, 0);
674 
675  CMatrixFloat x(16, 16), y(16, 16);
676  for (int i = 0; i < x.rows(); i++)
677  for (int j = 0; j < x.cols(); j++)
678  {
679  x(i, j) = sin(0.3 * i);
680  y(i, j) = cos(0.3 * i);
681  }
682  obj->setVectorField(x, y);
683  obj->setPointColor(1, 0.3f, 0);
684  obj->setVectorFieldColor(0, 0, 1);
685  obj->setPointSize(3.0);
686  obj->setLineWidth(2.0);
687  obj->setGridCenterAndCellSize(0, 0, 1.2f, 1.2f);
688  obj->adjustVectorFieldToGrid();
689  theScene->insert(obj);
690  }
691 
692  auto gl_txt = opengl::CText::Create("CVectorField2D");
693  gl_txt->setLocation(off_x, off_y_label, 0);
694  theScene->insert(gl_txt);
695  }
696  off_x += STEP_X;
697 
698  // CVectorField3D
699  {
700  {
701  const unsigned int num = 20;
702  const float scale = 0.8 * STEP_X / num;
703  auto obj = opengl::CVectorField3D::Create();
704  obj->setLocation(off_x, -0.5 * scale * num, 0); //
705 
706  CMatrixFloat x(num, num), y(num, num), z(num, num);
707  CMatrixFloat vx(num, num), vy(num, num), vz(num, num);
708  for (int i = 0; i < x.rows(); i++)
709  for (int j = 0; j < x.cols(); j++)
710  {
711  x(i, j) = (i - 0.5 * num) * scale;
712  y(i, j) = j * scale;
713  z(i, j) = 3 * sin(0.3 * i) * cos(0.3 * j);
714  vx(i, j) = 0.4 * sin(0.3 * i);
715  vy(i, j) = 0.8 * cos(0.3 * i);
716  vz(i, j) = 0.01 * i * j;
717  }
718  obj->setPointCoordinates(x, y, z);
719  obj->setVectorField(vx, vy, vz);
720  obj->setPointColor(1, 0.3f, 0);
721  obj->setVectorFieldColor(0, 0, 1);
722  obj->setPointSize(3.0);
723  obj->setLineWidth(2.0);
724  obj->enableColorFromModule();
725  obj->setMaxSpeedForColor(3.0);
726  obj->setMotionFieldColormap(0, 0, 1, 1, 0, 0);
727  theScene->insert(obj);
728  }
729 
730  auto gl_txt = opengl::CText::Create("CVectorField3D");
731  gl_txt->setLocation(off_x, off_y_label, 0);
732  theScene->insert(gl_txt);
733  }
734  off_x += STEP_X;
735 
736  // stock_objects::BumblebeeCamera
737  {
738  {
740  obj->setLocation(off_x, 0, 0);
741  theScene->insert(obj);
742  }
743 
744  auto gl_txt = opengl::CText::Create("stock_objects::BumblebeeCamera()");
745  gl_txt->setLocation(off_x, off_y_label, 0);
746  theScene->insert(gl_txt);
747  }
748  off_x += STEP_X;
749 
750  // stock_objects::CornerXYSimple
751  {
752  {
753  auto obj = opengl::stock_objects::CornerXYSimple(1, 3);
754  obj->setLocation(off_x, 0, 0);
755  theScene->insert(obj);
756  }
757 
758  auto gl_txt = opengl::CText::Create("stock_objects::CornerXYSimple()");
759  gl_txt->setLocation(off_x, off_y_label, 0);
760  theScene->insert(gl_txt);
761  }
762  off_x += STEP_X;
763 
764  // stock_objects::CornerXYZSimple
765  {
766  {
768  obj->setLocation(off_x, 0, 0);
769  theScene->insert(obj);
770  }
771 
772  auto gl_txt = opengl::CText::Create("stock_objects::CornerXYZSimple()");
773  gl_txt->setLocation(off_x, off_y_label, 0);
774  theScene->insert(gl_txt);
775  }
776  off_x += STEP_X;
777 
778  // stock_objects::CornerXYZ
779  {
780  {
782  obj->setLocation(off_x, 0, 0);
783  theScene->insert(obj);
784  }
785 
786  auto gl_txt = opengl::CText::Create("stock_objects::CornerXYZ()");
787  gl_txt->setLocation(off_x, off_y_label, 0);
788  theScene->insert(gl_txt);
789  }
790  off_x += STEP_X;
791 
792  // CSetOfTriangles: tested via stock_objects:
793  // stock_objects::RobotPioneer
794  {
795  {
797  obj->setLocation(off_x, 0, 0);
798  theScene->insert(obj);
799  }
800 
801  auto gl_txt = opengl::CText::Create("stock_objects::RobotPioneer()");
802  gl_txt->setLocation(off_x, off_y_label, 0);
803  theScene->insert(gl_txt);
804  }
805  off_x += STEP_X;
806 
807  // stock_objects::Hokuyo_URG
808  {
809  {
811  obj->setLocation(off_x, 0, 0);
812  theScene->insert(obj);
813  }
814 
815  auto gl_txt = opengl::CText::Create("stock_objects::Hokuyo_URG()");
816  gl_txt->setLocation(off_x, off_y_label, 0);
817  theScene->insert(gl_txt);
818  }
819  off_x += STEP_X;
820 
821  // stock_objects::Hokuyo_UTM
822  {
823  {
825  obj->setLocation(off_x, 0, 0);
826  theScene->insert(obj);
827  }
828 
829  auto gl_txt = opengl::CText::Create("stock_objects::Hokuyo_UTM()");
830  gl_txt->setLocation(off_x, off_y_label, 0);
831  theScene->insert(gl_txt);
832  }
833  off_x += STEP_X;
834 
835  // stock_objects::Househam_Sprayer
836  {
837  {
839  obj->setLocation(off_x, 0, 0);
840  theScene->insert(obj);
841  }
842 
843  auto gl_txt =
844  opengl::CText::Create("stock_objects::Househam_Sprayer()");
845  gl_txt->setLocation(off_x, off_y_label, 0);
846  theScene->insert(gl_txt);
847  }
848  off_x += STEP_X;
849 
850  // stock_objects::RobotRhodon
851  {
852  {
854  obj->setLocation(off_x, 0, 0);
855  theScene->insert(obj);
856  }
857 
858  auto gl_txt = opengl::CText::Create("stock_objects::RobotRhodon()");
859  gl_txt->setLocation(off_x, off_y_label, 0);
860  theScene->insert(gl_txt);
861  }
862  off_x += STEP_X;
863 
864  // CPlanarLaserScan
865  {
867  obj->setPose(mrpt::poses::CPose3D(off_x, 0, 0, 90.0_deg, 0, 0));
868 
871 
872  obj->setScan(scan);
873 
874  theScene->insert(obj);
875 
876  auto gl_txt = opengl::CText::Create("CPlanarLaserScan");
877  gl_txt->setLocation(off_x, off_y_label, 0);
878  theScene->insert(gl_txt);
879  }
880  off_x += STEP_X;
881 
882  // CTexturedPlane
883  {
884  mrpt::img::CImage pic, picAlpha;
885  const size_t W = 256, H = 256;
886  pic.resize(W, H, mrpt::img::CH_RGB);
887  picAlpha.resize(W, H, mrpt::img::CH_GRAY);
888  pic.filledRectangle(0, 0, W - 1, H - 1, mrpt::img::TColor::black());
889  pic.filledRectangle(0, 0, W / 4, H / 2, mrpt::img::TColor::white());
890 
891  picAlpha.filledRectangle(
892  0, 0, W - 1, H - 1, mrpt::img::TColor(0x55, 0x55, 0x55));
893  picAlpha.filledRectangle(
894  0, 0, W / 4, H / 2, mrpt::img::TColor(0xa0, 0xa0, 0xa0));
895 
896  {
897  opengl::CTexturedPlane::Ptr obj = opengl::CTexturedPlane::Create();
898  obj->setPose(mrpt::poses::CPose3D(off_x, 0, 0, 0, 90.0_deg, 0));
899  obj->assignImage(pic);
900  theScene->insert(obj);
901  }
902 
903  {
904  opengl::CTexturedPlane::Ptr obj = opengl::CTexturedPlane::Create();
905  obj->setPose(mrpt::poses::CPose3D(off_x, 4.0, 0, 0, 90.0_deg, 0));
906  obj->assignImage(pic, picAlpha);
907  theScene->insert(obj);
908  }
909 
910  auto gl_txt = opengl::CText::Create("CTexturedPlane");
911  gl_txt->setLocation(off_x, off_y_label, 0);
912  theScene->insert(gl_txt);
913  }
914  off_x += STEP_X;
915 
916  // COctoMapVoxels
917  {
918  mrpt::maps::COctoMap map(0.2);
919  // Insert 2D scan:
920 
923  map.insertObservation(scan1);
924 
925  auto gl_map1 = mrpt::opengl::COctoMapVoxels::Create();
926  auto gl_map2 = mrpt::opengl::COctoMapVoxels::Create();
927  auto gl_map3 = mrpt::opengl::COctoMapVoxels::Create();
928 
929  map.getAsOctoMapVoxels(*gl_map1);
930 
931  map.getAsOctoMapVoxels(*gl_map2);
932 
933  // map.renderingOptions.generateGridLines = true;
934  map.getAsOctoMapVoxels(*gl_map3);
935 
936  gl_map1->showGridLines(false);
937  gl_map1->showVoxelsAsPoints(true);
938  gl_map1->setPointSize(3.0);
939  gl_map1->setLocation(off_x, 0, 0);
940  theScene->insert(gl_map1);
941 
942  gl_map2->showVoxelsAsPoints(false);
943  gl_map2->showVoxels(VOXEL_SET_OCCUPIED, true);
944  gl_map2->showVoxels(VOXEL_SET_FREESPACE, true);
945  gl_map2->setLocation(off_x, 4, 0);
946  theScene->insert(gl_map2);
947 
948  gl_map3->showVoxelsAsPoints(true);
949  gl_map3->showGridLines(true);
950  gl_map3->setLocation(off_x, 8, 0);
951  theScene->insert(gl_map3);
952 
953  auto gl_txt = opengl::CText::Create("COctoMapVoxels");
954  gl_txt->setLocation(off_x, off_y_label, 0);
955  theScene->insert(gl_txt);
956  }
957  off_x += STEP_X;
958 
959  // Add image-mode viewport:
960  {
961  const std::string img_file = mrpt::system::getShareMRPTDir() +
962  "datasets/stereo-calib/0_left.jpg"s;
963 
965  if (im.loadFromFile(img_file))
966  {
967  auto glView = theScene->createViewport("image1");
968  glView->setViewportPosition(0.7, 0, 0.3, 0.3);
969  glView->setImageView(im);
970 
971  glView->setBorderSize(1);
972  }
973  }
974 
975  // Zoom out:
976  win.setCameraZoom(250);
977 
978  // IMPORTANT!!! IF NOT UNLOCKED, THE WINDOW WILL NOT BE UPDATED!
979  win.unlockAccess3DScene();
980  win.repaint();
981 
982  cout << "Close the window to end.\n";
983 
985  fp.vfont_scale = 14; // pixels
986  fp.draw_shadow = true;
987  win.addTextMessage(5, 5, "", 0 /*id*/, fp);
988 
989  while (win.isOpen())
990  {
991  win.updateTextMessage(
992  0 /*id*/,
993  format("Render time=%.03fms", 1e3 / win.getRenderingFPS()));
994  std::this_thread::sleep_for(2ms);
995  win.repaint();
996  }
997 }
998 
999 // ------------------------------------------------------
1000 // MAIN
1001 // ------------------------------------------------------
1002 int main()
1003 {
1004  try
1005  {
1007 
1008  return 0;
1009  }
1010  catch (const std::exception& e)
1011  {
1012  std::cerr << "MRPT error: " << mrpt::exception_to_str(e) << std::endl;
1013  return -1;
1014  }
1015  catch (...)
1016  {
1017  printf("Untyped exception!!");
1018  return -1;
1019  }
1020 }
CSetOfObjects::Ptr Hokuyo_UTM()
Returns a simple 3D model of a Hokuyo UTM scanner.
A compile-time fixed-size numeric matrix container.
Definition: CMatrixFixed.h:33
static CPose3D FromString(const std::string &s)
Definition: CPose3D.h:644
std::string getShareMRPTDir()
Attempts to find the directory [PREFIX/]share/mrpt/ and returns its absolute path, or empty string if not found.
Definition: filesystem.cpp:641
CSetOfObjects::Ptr CornerXYSimple(float scale=1.0, float lineWidth=1.0)
Returns two arrows representing a X,Y 2D corner (just thick lines, fast to render).
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
static Ptr Create(Args &&... args)
TPoint3Df TVector3Df
Definition: TPoint3D.h:274
size_t OCTREE_RENDER_MAX_POINTS_PER_NODE()
Default value = 1e5.
Definition: CPointCloud.cpp:39
A description of a bitmapped or vectorized text font.
Definition: opengl_fonts.h:36
void example2DRangeScan(mrpt::obs::CObservation2DRangeScan &s, int i=0)
Example 2D lidar scans (form a venerable SICK LMS200).
CSetOfObjects::Ptr RobotRhodon()
Returns a representation of Rhodon.
CSetOfObjects::Ptr Househam_Sprayer()
Returns a simple 3D model of a househam sprayer.
STL namespace.
bool loadFromFile(const std::string &fileName, int isColor=-1)
Load image from a file, whose format is determined from the extension (internally uses OpenCV)...
Definition: CImage.cpp:305
This base provides a set of functions for maths stuff.
size_t getWidth() const override
Returns the width of the image in pixels.
Definition: CImage.cpp:818
void resize(std::size_t width, std::size_t height, TImageChannels nChannels, PixelDepth depth=PixelDepth::D8U)
Changes the size of the image, erasing previous contents (does NOT scale its current content...
Definition: CImage.cpp:247
[New in MRPT 1.5.0]
Definition: color_maps.h:37
virtual void filledRectangle(int x0, int y0, int x1, int y1, const mrpt::img::TColor color)
Draws a filled rectangle.
Definition: CCanvas.cpp:205
static constexpr TColor black()
Definition: TColor.h:69
TPoint3D_< double > TPoint3D
Lightweight 3D point.
Definition: TPoint3D.h:268
static Ptr Create(Args &&... args)
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
Definition: COctoMap.h:40
mrpt::gui::CDisplayWindow3D::Ptr win
CSetOfObjects::Ptr RobotPioneer()
Returns a representation of a Pioneer II mobile base.
return_t square(const num_t x)
Inline function for the square of a number.
TPoint3D_< T > unitarize() const
Returns this vector with unit length: v/norm(v)
Definition: TPoint3D.h:153
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::math::TVector3Df direction
Light direction (must be normalized)
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
CSetOfObjects::Ptr CornerXYZSimple(float scale=1.0, float lineWidth=1.0)
Returns three arrows representing a X,Y,Z 3D corner (just thick lines instead of complex arrows for f...
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
std::string exception_to_str(const std::exception &e)
Builds a nice textual representation of a nested exception, which if generated using MRPT macros (THR...
Definition: exceptions.cpp:59
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:14
A RGB color - 8bit.
Definition: TColor.h:25
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
This template class provides the basic functionality for a general 2D any-size, resizable container o...
static constexpr TColor white()
Definition: TColor.h:70
CSetOfObjects::Ptr BumblebeeCamera()
Returns a simple 3D model of a PointGrey Bumblebee stereo camera.
Lighting parameters, mostly for triangle shaders.
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:148
float vfont_scale
Size of characters [pixels].
Definition: opengl_fonts.h:44
void TestOpenGLObjects()
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time.
CSetOfObjects::Ptr Hokuyo_URG()
Returns a simple 3D model of a Hokuyo URG scanner.



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020