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 
16 #include <mrpt/system/os.h>
17 #include <iostream>
18 
19 // ------------------------------------------------------
20 // TestGridMap3D
21 // ------------------------------------------------------
22 void TestGridMap3D()
23 {
25  const float resolution = 0.10; // [meters]
26  map.setSize(
27  mrpt::math::TPoint3D(-3, -5, -2), mrpt::math::TPoint3D(10, 5, 2),
28  resolution);
29 
30  // Insert 2D scan:
31  {
34  map.insertObservation(scan1);
35  }
36 
37  mrpt::gui::CDisplayWindow3D win("GridMap3D demo", 640, 480);
38 
40 
41  {
42  mrpt::opengl::COpenGLScene::Ptr& scene = win.get3DSceneAndLock();
43 
44  {
46  mrpt::opengl::CGridPlaneXY::Create(-20, 20, -20, 20, 0, 1);
47  gl_grid->setColor_u8(mrpt::img::TColor(0x80, 0x80, 0x80));
48  scene->insert(gl_grid);
49  }
50 
52  map.getAsOctoMapVoxels(*gl_map);
53 
54  gl_map->showGridLines(false);
55  gl_map->showVoxels(mrpt::opengl::VOXEL_SET_OCCUPIED, true);
56  gl_map->showVoxels(mrpt::opengl::VOXEL_SET_FREESPACE, true);
57  scene->insert(gl_map);
58 
59  win.unlockAccess3DScene();
60  }
61 
62  std::cout << "Close the window to exit" << std::endl;
63 
64  bool update_msg = true;
65 
66  while (win.isOpen())
67  {
68  if (win.keyHit())
69  {
70  const unsigned int k = win.getPushedKey();
71 
72  switch (k)
73  {
74  case 'g':
75  case 'G':
76  gl_map->showGridLines(!gl_map->areGridLinesVisible());
77  break;
78  case 'f':
79  case 'F':
80  gl_map->showVoxels(
82  !gl_map->areVoxelsVisible(
84  break;
85  case 'o':
86  case 'O':
87  gl_map->showVoxels(
89  !gl_map->areVoxelsVisible(
91  break;
92  case 'l':
93  case 'L':
94  gl_map->enableLights(!gl_map->areLightsEnabled());
95  break;
96  };
97  update_msg = true;
98  }
99 
100  if (update_msg)
101  {
102  update_msg = false;
103 
104  win.addTextMessage(
105  5, 5,
106  mrpt::format(
107  "Commands: 'g' (grids=%s) | 'f' (freespace=%s) | 'o' "
108  "(occupied=%s) | 'l' (lights=%s)",
109  gl_map->areGridLinesVisible() ? "YES" : "NO",
110  gl_map->areVoxelsVisible(mrpt::opengl::VOXEL_SET_FREESPACE)
111  ? "YES"
112  : "NO",
113  gl_map->areVoxelsVisible(mrpt::opengl::VOXEL_SET_OCCUPIED)
114  ? "YES"
115  : "NO",
116  gl_map->areLightsEnabled() ? "YES" : "NO"));
117 
118  win.repaint();
119  }
120 
121  using namespace std::chrono_literals;
122  std::this_thread::sleep_for(10ms);
123  };
124 }
125 
126 int main([[maybe_unused]] int argc, [[maybe_unused]] char** argv)
127 {
128  try
129  {
130  TestGridMap3D();
131  return 0;
132  }
133  catch (const std::exception& e)
134  {
135  std::cerr << mrpt::exception_to_str(e) << std::endl;
136  return -1;
137  }
138 }
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
void example2DRangeScan(mrpt::obs::CObservation2DRangeScan &s, int i=0)
Example 2D lidar scans (form a venerable SICK LMS200).
void TestGridMap3D()
void setSize(const mrpt::math::TPoint3D &corner_min, const mrpt::math::TPoint3D &corner_max, double resolution, float default_value=0.5f)
Change the size of gridmap, erasing all its previous contents.
static Ptr Create(Args &&... args)
mrpt::gui::CDisplayWindow3D::Ptr win
void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const
A 3D occupancy grid map with a regular, even distribution of voxels.
const char * argv[]
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
bool generateGridLines
Generate grid lines for all octree nodes, useful to draw the "structure" of the octree, but computationally costly (Default: false)
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
const int argc
A RGB color - 8bit.
Definition: TColor.h:25
static Ptr Create(Args &&... args)
Definition: CGridPlaneXY.h:31
bool insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr)
Insert the observation information into this map.
Definition: CMetricMap.cpp:93
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time.



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