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>
16 #include <mrpt/system/os.h>
17 #include <iostream>
18 
19 //#define HAS_SYSTEM_OCTOMAP
20 
21 #ifdef HAS_SYSTEM_OCTOMAP
22 #include <octomap/OcTree.h>
23 #include <octomap/octomap.h>
24 #endif
25 
26 using namespace mrpt;
27 using namespace mrpt::maps;
28 using namespace mrpt::opengl;
29 using namespace mrpt::math;
30 using namespace mrpt::obs;
31 using namespace std;
32 
33 // ------------------------------------------------------
34 // TestOctoMap
35 // ------------------------------------------------------
36 void TestOctoMap()
37 {
38  COctoMap map(0.2);
39 
40  if (false)
41  {
42  // Manually update voxels:
43  map.updateVoxel(1, 1, 1, true); // integrate 'occupied' measurement
44 
45  map.updateVoxel(1.5, 1, 1, true); // integrate 'occupied' measurement
46  map.updateVoxel(1.5, 1, 1, true); // integrate 'occupied' measurement
47  map.updateVoxel(1.5, 1, 1, true); // integrate 'occupied' measurement
48 
49  map.updateVoxel(-1, -1, 1, false); // integrate 'occupied' measurement
50 
51  double occup;
52  bool is_mapped;
54 
55  pt = mrpt::math::TPoint3D(1, 1, 1);
56  is_mapped = map.getPointOccupancy(pt.x, pt.y, pt.z, occup);
57  cout << "pt: " << pt << " is mapped?: " << (is_mapped ? "YES" : "NO")
58  << " occupancy: " << occup << endl;
59 
60  pt = mrpt::math::TPoint3D(-1, -1, 1);
61  is_mapped = map.getPointOccupancy(pt.x, pt.y, pt.z, occup);
62  cout << "pt: " << pt << " is mapped?: " << (is_mapped ? "YES" : "NO")
63  << " occupancy: " << occup << endl;
64  }
65 
66  // Insert 2D scan:
67  {
70  map.insertObservation(scan1);
71  }
72 
73  mrpt::gui::CDisplayWindow3D win("OctoMap demo", 640, 480);
74 
77 
78  {
79  mrpt::opengl::COpenGLScene::Ptr& scene = win.get3DSceneAndLock();
80 
81  {
83  mrpt::opengl::CGridPlaneXY::Create(-20, 20, -20, 20, 0, 1);
84  gl_grid->setColor_u8(mrpt::img::TColor(0x80, 0x80, 0x80));
85  scene->insert(gl_grid);
86  }
87 
88  map.renderingOptions.generateGridLines = true;
89  map.getAsOctoMapVoxels(*gl_map);
90 
91  gl_map->showGridLines(false);
92  gl_map->showVoxels(VOXEL_SET_OCCUPIED, true);
93  gl_map->showVoxels(VOXEL_SET_FREESPACE, true);
94  scene->insert(gl_map);
95 
96  win.unlockAccess3DScene();
97  }
98 
99 // Go through voxels:
100 #ifdef HAS_SYSTEM_OCTOMAP
101  {
102  const auto& om = map.getOctomap<octomap::OcTree>();
103  for (auto it = om.begin_leafs(); it != om.end_leafs(); ++it)
104  {
105  const octomap::point3d pt = it.getCoordinate();
106  cout << "pt: " << pt << " -> occupancy = " << it->getOccupancy()
107  << endl;
108  }
109  }
110 #endif
111 
112  cout << "Close the window to exit" << endl;
113 
114  bool update_msg = true;
115 
116  while (win.isOpen())
117  {
118  if (win.keyHit())
119  {
120  const unsigned int k = win.getPushedKey();
121 
122  switch (k)
123  {
124  case 'g':
125  case 'G':
126  gl_map->showGridLines(!gl_map->areGridLinesVisible());
127  break;
128  case 'f':
129  case 'F':
130  gl_map->showVoxels(
132  !gl_map->areVoxelsVisible(VOXEL_SET_FREESPACE));
133  break;
134  case 'o':
135  case 'O':
136  gl_map->showVoxels(
138  !gl_map->areVoxelsVisible(VOXEL_SET_OCCUPIED));
139  break;
140  case 'l':
141  case 'L':
142  gl_map->enableLights(!gl_map->areLightsEnabled());
143  break;
144  };
145  update_msg = true;
146  }
147 
148  if (update_msg)
149  {
150  update_msg = false;
151 
152  win.addTextMessage(
153  5, 5,
154  mrpt::format(
155  "Commands: 'g' (grids=%s) | 'f' (freespace=%s) | 'o' "
156  "(occupied=%s) | 'l' (lights=%s)",
157  gl_map->areGridLinesVisible() ? "YES" : "NO",
158  gl_map->areVoxelsVisible(VOXEL_SET_FREESPACE) ? "YES"
159  : "NO",
160  gl_map->areVoxelsVisible(VOXEL_SET_OCCUPIED) ? "YES" : "NO",
161  gl_map->areLightsEnabled() ? "YES" : "NO"));
162 
163  win.repaint();
164  }
165 
166  std::this_thread::sleep_for(10ms);
167  };
168 }
169 
170 int main(int argc, char** argv)
171 {
172  try
173  {
174  TestOctoMap();
175  return 0;
176  }
177  catch (exception& e)
178  {
179  cout << "MRPT exception caught: " << e.what() << endl;
180  return -1;
181  }
182  catch (...)
183  {
184  printf("Another exception!!");
185  return -1;
186  }
187 }
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).
STL namespace.
This base provides a set of functions for maths stuff.
This namespace contains representation of robot actions and observations.
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
T x
X,Y,Z coordinates.
Definition: TPoint3D.h:29
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
const char * argv[]
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:13
const int argc
A RGB color - 8bit.
Definition: TColor.h:25
static Ptr Create(Args &&... args)
Definition: CGridPlaneXY.h:31
void TestOctoMap()
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