41 theScene->getViewport()->lightParameters();
46 const double off_y_label = 20;
47 const double STEP_X = 25;
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);
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);
67 auto gl_txt = opengl::CText::Create(
"CGridPlaneXY");
68 gl_txt->setLocation(off_x, off_y_label, 0);
69 theScene->insert(gl_txt);
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);
80 auto gl_txt = opengl::CText::Create(
"CGridPlaneXZ");
81 gl_txt->setLocation(off_x, off_y_label, 0);
82 theScene->insert(gl_txt);
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);
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);
100 auto gl_txt = opengl::CText::Create(
"CArrow");
101 gl_txt->setLocation(off_x, off_y_label, 0);
102 theScene->insert(gl_txt);
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);
112 auto gl_txt = opengl::CText::Create(
"CAxis");
113 gl_txt->setLocation(off_x, off_y_label, 0);
114 theScene->insert(gl_txt);
120 auto obj = opengl::CBox::Create(
122 obj->setLocation(off_x, 0, 0);
123 theScene->insert(obj);
127 obj2->setLocation(off_x, 4, 0);
128 theScene->insert(obj2);
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);
138 auto gl_txt = opengl::CText::Create(
"CBox");
139 gl_txt->setLocation(off_x, off_y_label, 0);
140 theScene->insert(gl_txt);
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);
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);
155 auto gl_txt = opengl::CText::Create(
"CFrustum");
156 gl_txt->setLocation(off_x, off_y_label, 0);
157 theScene->insert(gl_txt);
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);
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);
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);
178 auto gl_txt = opengl::CText::Create(
"CCylinder");
179 gl_txt->setLocation(off_x, off_y_label, 0);
180 theScene->insert(gl_txt);
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);
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);
200 auto gl_txt = opengl::CText::Create(
"CDisk");
201 gl_txt->setLocation(off_x, off_y_label, 0);
202 theScene->insert(gl_txt);
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};
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);
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);
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);
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);
246 auto gl_txt = opengl::CText::Create(
"CEllipsoid3D");
247 gl_txt->setLocation(off_x, off_y_label, 0);
248 theScene->insert(gl_txt);
254 const double cov_params_dat[] = {0.2, 0, 0, 0.1};
255 const double mean_params_dat[] = {3.0, 0.5};
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);
265 theScene->insert(obj);
268 obj_corner->setLocation(off_x, 6, 0);
269 theScene->insert(obj_corner);
273 const double cov_params_dat[] = {0.2, 0.09, 0.09, 0.1};
274 const double mean_params_dat[] = {5.0, -0.5};
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);
284 theScene->insert(obj);
287 obj_corner->setLocation(off_x, 0, 0);
288 theScene->insert(obj_corner);
291 auto gl_txt = opengl::CText::Create(
"CEllipsoidRangeBearing2D");
292 gl_txt->setLocation(off_x, off_y_label, 0);
293 theScene->insert(gl_txt);
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);
305 const double cov_params_dat[] = {
square(rho_std), 0, 0,
307 const double mean_params_dat[] = {rho_mean, 70.0_deg};
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);
320 obj_corner->setLocation(off_x, 6, 0);
321 theScene->insert(obj_corner);
324 auto gl_txt = opengl::CText::Create(
"CEllipsoidInverseDepth2D");
325 gl_txt->setLocation(off_x, off_y_label, 0);
326 theScene->insert(gl_txt);
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);
338 const double cov_params_dat[] = {
square(rho_std), 0, 0, 0,
341 const double mean_params_dat[] = {rho_mean, 30.0_deg, -45.0_deg};
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);
351 theScene->insert(obj);
354 obj_corner->setLocation(off_x, 0, 0);
355 theScene->insert(obj_corner);
358 auto gl_txt = opengl::CText::Create(
"CEllipsoidInverseDepth3D");
359 gl_txt->setLocation(off_x, off_y_label, 0);
360 theScene->insert(gl_txt);
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);
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];
380 unsigned int first_ind = 0;
381 for (
unsigned int u = 0; u < cols; u++)
383 for (
unsigned int v = 0; v < rows; v++)
385 const unsigned int face_ind = v + u * rows;
386 vert_per_face[face_ind] = 4;
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;
399 for (
unsigned int u = 0; u <= cols; u++)
400 for (
unsigned int v = 0; v <= rows; v++)
402 const unsigned int vert_ind = v + u * (rows + 1);
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);
415 num_verts, num_faces, vert_per_face, face_verts, vert_coords);
416 theScene->insert(obj);
418 auto gl_txt = opengl::CText::Create(
"CMesh3D");
419 gl_txt->setLocation(off_x, off_y_label, 0);
420 theScene->insert(gl_txt);
431 obj1->setXBounds(-1, 1);
432 obj1->setYBounds(-1, 1);
434 const int W = 128, H = 128;
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);
443 "datasets/sample-texture-terrain.jpg"s;
449 obj1->enableColorFromZ(
true);
450 obj1->setPointSize(2.0);
451 obj1->setLocation(off_x, 0, 0);
452 theScene->insert(obj1);
457 obj2->assignImageAndZ(im, Z);
458 obj2->setPointSize(2.0);
459 obj2->setLocation(off_x, 3, 0);
460 theScene->insert(obj2);
463 auto gl_txt = opengl::CText::Create(
"CMeshFast");
464 gl_txt->setLocation(off_x, off_y_label, 0);
465 theScene->insert(gl_txt);
473 obj3->enableWireFrame(
true);
474 obj3->setLocation(off_x, 0, 0);
475 theScene->insert(obj3);
480 obj4->assignImageAndZ(im, Z);
481 obj4->setLocation(off_x, 3, 0);
482 theScene->insert(obj4);
486 auto gl_txt = opengl::CText::Create(
"CMesh");
487 gl_txt->setLocation(off_x, off_y_label, 0);
488 theScene->insert(gl_txt);
495 auto obj = opengl::CPointCloud::Create();
496 obj->setLocation(off_x, 0, 0);
497 theScene->insert(obj);
499 obj->setPointSize(1.0);
500 obj->enableColorFromY();
502 for (
int i = 0; i < 100000; i++)
504 rng.drawUniform<
float>(-5, 5), rng.drawUniform<
float>(-5, 5),
505 rng.drawUniform<
float>(-5, 5));
507 auto gl_txt = opengl::CText::Create(
"CPointCloud");
508 gl_txt->setLocation(off_x, off_y_label, 0);
509 theScene->insert(gl_txt);
515 auto obj = opengl::CPointCloudColoured::Create();
516 obj->setLocation(off_x, 0, 0);
517 theScene->insert(obj);
519 obj->setPointSize(1.0);
521 for (
int i = 0; i < 200; i++)
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));
527 auto gl_txt = opengl::CText::Create(
"CPointCloudColoured");
528 gl_txt->setLocation(off_x, off_y_label, 0);
529 theScene->insert(gl_txt);
536 auto obj = opengl::CPolyhedron::CreateCuboctahedron(1.0);
537 obj->setLocation(off_x, 0, 0);
538 obj->setWireframe(
true);
539 theScene->insert(obj);
542 auto obj = opengl::CPolyhedron::CreateDodecahedron(1.0);
543 obj->setLocation(off_x, -5, 0);
544 theScene->insert(obj);
547 auto obj = opengl::CPolyhedron::CreateIcosahedron(1.0);
548 obj->setLocation(off_x, 5, 0);
549 theScene->insert(obj);
552 auto gl_txt = opengl::CText::Create(
"CPolyhedron");
553 gl_txt->setLocation(off_x, off_y_label, 0);
554 theScene->insert(gl_txt);
561 auto obj = opengl::CSphere::Create(3.0);
562 obj->setLocation(off_x, 0, 0);
563 theScene->insert(obj);
566 auto gl_txt = opengl::CText::Create(
"CSphere");
567 gl_txt->setLocation(off_x, off_y_label, 0);
568 theScene->insert(gl_txt);
575 auto obj = opengl::CText::Create(
576 "This is a CText example! My size is invariant to " 578 obj->setLocation(off_x, 0, 0);
579 theScene->insert(obj);
582 auto gl_txt = opengl::CText::Create(
"CText");
583 gl_txt->setLocation(off_x, off_y_label, 0);
584 theScene->insert(gl_txt);
591 auto obj = opengl::CText3D::Create(
"I'm a cool CText3D!");
592 obj->setLocation(off_x, 0, 0);
593 theScene->insert(obj);
597 auto obj = opengl::CText3D::Create(
"A rotated CText3D");
601 theScene->insert(obj);
604 auto gl_txt = opengl::CText::Create(
"CText3D");
605 gl_txt->setLocation(off_x, off_y_label, 0);
606 theScene->insert(gl_txt);
613 auto obj = opengl::CColorBar::Create(
616 obj->setLocation(off_x, 0, 0);
617 theScene->insert(obj);
620 auto gl_txt = opengl::CText::Create(
"CColorBar");
621 gl_txt->setLocation(off_x, off_y_label, 0);
622 theScene->insert(gl_txt);
628 for (
int rep = 0; rep < 2; rep++)
630 auto obj = opengl::CSetOfLines::Create();
631 obj->setLocation(off_x, rep * 20, 0);
633 for (
int i = 0; i < 15; i++)
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));
639 if (rep == 1) obj->setVerticesPointSize(5.0f);
640 theScene->insert(obj);
643 auto gl_txt = opengl::CText::Create(
"CSetOfLines");
644 gl_txt->setLocation(off_x, off_y_label, 0);
645 theScene->insert(gl_txt);
652 auto obj = opengl::CSimpleLine::Create();
653 obj->setLocation(off_x, 0, 0);
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));
660 theScene->insert(obj);
663 auto gl_txt = opengl::CText::Create(
"CSimpleLine");
664 gl_txt->setLocation(off_x, off_y_label, 0);
665 theScene->insert(gl_txt);
672 auto obj = opengl::CVectorField2D::Create();
673 obj->setLocation(off_x, 0, 0);
676 for (
int i = 0; i < x.rows(); i++)
677 for (
int j = 0; j < x.cols(); j++)
679 x(i, j) = sin(0.3 * i);
680 y(i, j) = cos(0.3 * i);
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);
692 auto gl_txt = opengl::CText::Create(
"CVectorField2D");
693 gl_txt->setLocation(off_x, off_y_label, 0);
694 theScene->insert(gl_txt);
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);
708 for (
int i = 0; i < x.rows(); i++)
709 for (
int j = 0; j < x.cols(); j++)
711 x(i, j) = (i - 0.5 * num) * 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;
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);
730 auto gl_txt = opengl::CText::Create(
"CVectorField3D");
731 gl_txt->setLocation(off_x, off_y_label, 0);
732 theScene->insert(gl_txt);
740 obj->setLocation(off_x, 0, 0);
741 theScene->insert(obj);
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);
754 obj->setLocation(off_x, 0, 0);
755 theScene->insert(obj);
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);
768 obj->setLocation(off_x, 0, 0);
769 theScene->insert(obj);
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);
782 obj->setLocation(off_x, 0, 0);
783 theScene->insert(obj);
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);
797 obj->setLocation(off_x, 0, 0);
798 theScene->insert(obj);
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);
811 obj->setLocation(off_x, 0, 0);
812 theScene->insert(obj);
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);
825 obj->setLocation(off_x, 0, 0);
826 theScene->insert(obj);
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);
839 obj->setLocation(off_x, 0, 0);
840 theScene->insert(obj);
844 opengl::CText::Create(
"stock_objects::Househam_Sprayer()");
845 gl_txt->setLocation(off_x, off_y_label, 0);
846 theScene->insert(gl_txt);
854 obj->setLocation(off_x, 0, 0);
855 theScene->insert(obj);
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);
874 theScene->insert(obj);
876 auto gl_txt = opengl::CText::Create(
"CPlanarLaserScan");
877 gl_txt->setLocation(off_x, off_y_label, 0);
878 theScene->insert(gl_txt);
885 const size_t W = 256, H = 256;
899 obj->assignImage(pic);
900 theScene->insert(obj);
906 obj->assignImage(pic, picAlpha);
907 theScene->insert(obj);
910 auto gl_txt = opengl::CText::Create(
"CTexturedPlane");
911 gl_txt->setLocation(off_x, off_y_label, 0);
912 theScene->insert(gl_txt);
923 map.insertObservation(scan1);
929 map.getAsOctoMapVoxels(*gl_map1);
931 map.getAsOctoMapVoxels(*gl_map2);
934 map.getAsOctoMapVoxels(*gl_map3);
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);
942 gl_map2->showVoxelsAsPoints(
false);
945 gl_map2->setLocation(off_x, 4, 0);
946 theScene->insert(gl_map2);
948 gl_map3->showVoxelsAsPoints(
true);
949 gl_map3->showGridLines(
true);
950 gl_map3->setLocation(off_x, 8, 0);
951 theScene->insert(gl_map3);
953 auto gl_txt = opengl::CText::Create(
"COctoMapVoxels");
954 gl_txt->setLocation(off_x, off_y_label, 0);
955 theScene->insert(gl_txt);
962 "datasets/stereo-calib/0_left.jpg"s;
967 auto glView = theScene->createViewport(
"image1");
968 glView->setViewportPosition(0.7, 0, 0.3, 0.3);
969 glView->setImageView(im);
971 glView->setBorderSize(1);
976 win.setCameraZoom(250);
979 win.unlockAccess3DScene();
982 cout <<
"Close the window to end.\n";
987 win.addTextMessage(5, 5,
"", 0 , fp);
991 win.updateTextMessage(
993 format(
"Render time=%.03fms", 1e3 /
win.getRenderingFPS()));
994 std::this_thread::sleep_for(2ms);
1010 catch (
const std::exception& e)
1017 printf(
"Untyped exception!!");
CSetOfObjects::Ptr Hokuyo_UTM()
Returns a simple 3D model of a Hokuyo UTM scanner.
A compile-time fixed-size numeric matrix container.
static CPose3D FromString(const std::string &s)
std::string getShareMRPTDir()
Attempts to find the directory [PREFIX/]share/mrpt/ and returns its absolute path, or empty string if not found.
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)
static Ptr Create(Args &&... args)
size_t OCTREE_RENDER_MAX_POINTS_PER_NODE()
Default value = 1e5.
A description of a bitmapped or vectorized text font.
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.
bool loadFromFile(const std::string &fileName, int isColor=-1)
Load image from a file, whose format is determined from the extension (internally uses OpenCV)...
This base provides a set of functions for maths stuff.
size_t getWidth() const override
Returns the width of the image in pixels.
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...
virtual void filledRectangle(int x0, int y0, int x1, int y1, const mrpt::img::TColor color)
Draws a filled rectangle.
static constexpr TColor black()
TPoint3D_< double > TPoint3D
Lightweight 3D point.
static Ptr Create(Args &&... args)
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
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)
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).
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.
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...
Classes for creating GUI windows for 2D and 3D visualization.
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()
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.
float vfont_scale
Size of characters [pixels].
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.