MRPT  1.9.9
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-2019, 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 
10 /*
11  Example : kinect-to-2d-laser-demo
12  Web page : https://www.mrpt.org/Example_Kinect_To_2D_laser_scan (includes
13  video demo)
14 
15  Purpose : Demonstrate grabbing from CKinect, multi-threading
16  and converting the 3D range data into an equivalent
17  2D planar scan.
18 */
19 
22 #include <mrpt/hwdrivers/CKinect.h>
23 #include <mrpt/img/TColor.h>
24 #include <mrpt/opengl/CFrustum.h>
29 #include <mrpt/system/CTicTac.h>
30 #include <mrpt/system/filesystem.h>
31 #include <iostream>
32 
33 using namespace mrpt;
34 using namespace mrpt::hwdrivers;
35 using namespace mrpt::math;
36 using namespace mrpt::gui;
37 using namespace mrpt::obs;
38 using namespace mrpt::maps;
39 using namespace mrpt::opengl;
40 using namespace mrpt::system;
41 using namespace mrpt::img;
42 using namespace std;
43 
44 // Thread for grabbing: Do this is another thread so we divide rendering and
45 // grabbing
46 // and exploit multicore CPUs.
47 struct TThreadParam
48 {
49  TThreadParam() {}
50  volatile bool quit{false};
51  volatile int pushed_key{0};
52  volatile double Hz{0};
53 
54  CObservation3DRangeScan::Ptr new_obs; // RGB+D (+3D points)
55  CObservationIMU::Ptr new_obs_imu; // Accelerometers
56 };
57 
59 {
60  try
61  {
62  CKinect kinect;
63 
64  // Set params:
65  // kinect.enableGrab3DPoints(true);
66  // kinect.enablePreviewRGB(true);
67  //...
68  const std::string cfgFile = "kinect_calib.cfg";
69  if (mrpt::system::fileExists(cfgFile))
70  {
71  cout << "Loading calibration from: " << cfgFile << endl;
72  kinect.loadConfig(mrpt::config::CConfigFile(cfgFile), "KINECT");
73  }
74  else
75  cerr << "Warning: Calibration file [" << cfgFile
76  << "] not found -> Using default params.\n";
77 
78  // Open:
79  cout << "Calling CKinect::initialize()...";
80  kinect.initialize();
81  cout << "OK\n";
82 
83  CTicTac tictac;
84  int nImgs = 0;
85  bool there_is_obs = true, hard_error = false;
86 
87  while (!hard_error && !p.quit)
88  {
89  // Grab new observation from the camera:
90  auto obs = CObservation3DRangeScan::Create(); // Smart pointers to
91  // observations
92  CObservationIMU::Ptr obs_imu = CObservationIMU::Create();
93 
94  kinect.getNextObservation(*obs, *obs_imu, there_is_obs, hard_error);
95 
96  if (!hard_error && there_is_obs)
97  {
98  std::atomic_store(&p.new_obs, obs);
99  std::atomic_store(&p.new_obs_imu, obs_imu);
100  }
101 
102  if (p.pushed_key != 0)
103  {
104  switch (p.pushed_key)
105  {
106  case 27:
107  p.quit = true;
108  break;
109  }
110 
111  // Clear pushed key flag:
112  p.pushed_key = 0;
113  }
114 
115  nImgs++;
116  if (nImgs > 10)
117  {
118  p.Hz = nImgs / tictac.Tac();
119  nImgs = 0;
120  tictac.Tic();
121  }
122  }
123  }
124  catch (const std::exception& e)
125  {
126  cout << "Exception in Kinect thread: " << e.what() << endl;
127  p.quit = true;
128  }
129 }
130 
131 // ------------------------------------------------------
132 // Test_Kinect
133 // ------------------------------------------------------
134 void Test_Kinect()
135 {
136  // Launch grabbing thread:
137  // --------------------------------------------------------
138  TThreadParam thrPar;
139  std::thread thHandle(thread_grabbing, std::ref(thrPar));
140 
141  // Wait until data stream starts so we can say for sure the sensor has been
142  // initialized OK:
143  cout << "Waiting for sensor initialization...\n";
144  do
145  {
146  CObservation3DRangeScan::Ptr possiblyNewObs =
147  std::atomic_load(&thrPar.new_obs);
148  if (possiblyNewObs && possiblyNewObs->timestamp != INVALID_TIMESTAMP)
149  break;
150  else
151  std::this_thread::sleep_for(10ms);
152  } while (!thrPar.quit);
153 
154  // Check error condition:
155  if (thrPar.quit) return;
156 
157  // Create window and prepare OpenGL object in the scene:
158  // --------------------------------------------------------
159  mrpt::gui::CDisplayWindow3D win3D("Kinect 3D -> 2D laser scan", 800, 600);
160 
161  win3D.setCameraAzimuthDeg(140);
162  win3D.setCameraElevationDeg(30);
163  win3D.setCameraZoom(10.0);
164  win3D.setFOV(90);
165  win3D.setCameraPointingToPoint(2.5, 0, 0);
166 
167  // The 3D point cloud OpenGL object:
170  gl_points->setPointSize(2.5);
171 
172  // The 2D "laser scan" OpenGL object:
175  gl_2d_scan->enablePoints(true);
176  gl_2d_scan->enableLine(true);
177  gl_2d_scan->enableSurface(true);
178  gl_2d_scan->setSurfaceColor(0, 0, 1, 0.3); // RGBA
179 
181  0.2f, 5.0f, 90.0f, 5.0f, 2.0f, true, true);
182 
183  const double aspect_ratio =
184  480.0 / 640.0; // kinect.rows() / double( kinect.cols() );
185 
187  viewInt; // Extra viewports for the RGB & D images.
188  {
189  mrpt::opengl::COpenGLScene::Ptr& scene = win3D.get3DSceneAndLock();
190 
191  // Create the Opengl object for the point cloud:
192  scene->insert(gl_points);
193  scene->insert(gl_2d_scan);
194  scene->insert(gl_frustum);
195 
196  {
199  gl_grid->setColor(0.6, 0.6, 0.6);
200  scene->insert(gl_grid);
201  }
202  {
205  gl_corner->setScale(0.2);
206  scene->insert(gl_corner);
207  }
208 
209  const int VW_WIDTH =
210  250; // Size of the viewport into the window, in pixel units.
211  const int VW_HEIGHT = aspect_ratio * VW_WIDTH;
212  const int VW_GAP = 30;
213 
214  // Create the Opengl objects for the planar images, as textured planes,
215  // each in a separate viewport:
216  win3D.addTextMessage(
217  30, -25 - 1 * (VW_GAP + VW_HEIGHT), "Range data", TColorf(1, 1, 1),
219  viewRange = scene->createViewport("view2d_range");
220  viewRange->setViewportPosition(
221  5, -10 - 1 * (VW_GAP + VW_HEIGHT), VW_WIDTH, VW_HEIGHT);
222 
223  win3D.addTextMessage(
224  30, -25 - 2 * (VW_GAP + VW_HEIGHT), "Intensity data",
226  viewInt = scene->createViewport("view2d_int");
227  viewInt->setViewportPosition(
228  5, -10 - 2 * (VW_GAP + VW_HEIGHT), VW_WIDTH, VW_HEIGHT);
229 
230  win3D.unlockAccess3DScene();
231  win3D.repaint();
232  }
233 
235  CObservationIMU::Ptr last_obs_imu;
236 
237  while (win3D.isOpen() && !thrPar.quit)
238  {
239  CObservation3DRangeScan::Ptr possiblyNewObs =
240  std::atomic_load(&thrPar.new_obs);
241  if (possiblyNewObs && possiblyNewObs->timestamp != INVALID_TIMESTAMP &&
242  (!last_obs || possiblyNewObs->timestamp != last_obs->timestamp))
243  {
244  // It IS a new observation:
245  last_obs = possiblyNewObs;
246  last_obs_imu = std::atomic_load(&thrPar.new_obs_imu);
247 
248  // Update visualization ---------------------------------------
249  bool do_refresh = false;
250 
251  // Show 2D ranges as a grayscale image:
252  if (last_obs->hasRangeImage)
253  {
255 
256  // Normalize the image
257  static CMatrixFloat range2D; // Static to save time allocating
258  // the matrix in every iteration
259  range2D = last_obs->rangeImage;
260  range2D *= (1.0 / last_obs->maxRange);
261 
262  img.setFromMatrix(range2D);
263 
264  win3D.get3DSceneAndLock();
265  viewRange->setImageView(std::move(img));
266  win3D.unlockAccess3DScene();
267  do_refresh = true;
268  }
269 
270  // Convert ranges to an equivalent 2D "fake laser" scan:
271  if (last_obs->hasRangeImage)
272  {
273  // Convert to scan:
275  CObservation2DRangeScan::Create();
276  const float vert_FOV = DEG2RAD(gl_frustum->getVertFOV());
277 
279  sp.angle_inf = .5f * vert_FOV;
280  sp.angle_sup = .5f * vert_FOV;
281  sp.sensorLabel = "KINECT_2D_SCAN";
282 
283  last_obs->convertTo2DScan(*obs_2d, sp);
284 
285  // And load scan in the OpenGL object:
286  gl_2d_scan->setScan(*obs_2d);
287  }
288 
289  // Show intensity image:
290  if (last_obs->hasIntensityImage)
291  {
292  win3D.get3DSceneAndLock();
293  viewInt->setImageView(
294  last_obs->intensityImage); // This is not "_fast" since the
295  // intensity image is used below
296  // in the coloured point cloud.
297  win3D.unlockAccess3DScene();
298  do_refresh = true;
299  }
300 
301  // Show 3D points:
302  if (last_obs->hasPoints3D)
303  {
304  win3D.get3DSceneAndLock();
307 
308  last_obs->project3DPointsFromDepthImageInto(*gl_points, pp);
309  win3D.unlockAccess3DScene();
310  do_refresh = true;
311  }
312 
313  // Some text messages:
314  win3D.get3DSceneAndLock();
315  // Estimated grabbing rate:
316  win3D.addTextMessage(
317  -100, -20, format("%.02f Hz", thrPar.Hz), TColorf(1, 1, 1),
318  "sans", 15, mrpt::opengl::FILL, 100);
319 
320  win3D.addTextMessage(
321  10, 10,
322  "'o'/'i'-zoom out/in, '2'/'3'/'f':show/hide 2D/3D/frustum "
323  "data, mouse: orbit 3D, ESC: quit",
324  TColorf(1, 1, 1), "sans", 10, mrpt::opengl::FILL, 110);
325 
326  win3D.addTextMessage(
327  10, 25,
328  format(
329  "Show: 3D=%s 2D=%s Frustum=%s (vert. FOV=%.1fdeg)",
330  gl_points->isVisible() ? "YES" : "NO",
331  gl_2d_scan->isVisible() ? "YES" : "NO",
332  gl_frustum->isVisible() ? "YES" : "NO",
333  gl_frustum->getVertFOV()),
334  TColorf(1, 1, 1), "sans", 10, mrpt::opengl::FILL, 111);
335  win3D.unlockAccess3DScene();
336 
337  // Do we have accelerometer data?
338  if (last_obs_imu && last_obs_imu->dataIsPresent[IMU_X_ACC])
339  {
340  win3D.get3DSceneAndLock();
341  win3D.addTextMessage(
342  10, 65,
343  format(
344  "Acc: x=%.02f y=%.02f z=%.02f",
345  last_obs_imu->rawMeasurements[IMU_X_ACC],
346  last_obs_imu->rawMeasurements[IMU_Y_ACC],
347  last_obs_imu->rawMeasurements[IMU_Z_ACC]),
348  TColorf(.7, .7, .7), "sans", 10, mrpt::opengl::FILL, 102);
349  win3D.unlockAccess3DScene();
350  do_refresh = true;
351  }
352 
353  // Force opengl repaint:
354  if (do_refresh) win3D.repaint();
355 
356  } // end update visualization:
357 
358  // Process possible keyboard commands:
359  // --------------------------------------
360  if (win3D.keyHit() && thrPar.pushed_key == 0)
361  {
362  const int key = tolower(win3D.getPushedKey());
363 
364  switch (key)
365  {
366  // Some of the keys are processed in this thread:
367  case 'o':
368  win3D.setCameraZoom(win3D.getCameraZoom() * 1.2);
369  win3D.repaint();
370  break;
371  case 'i':
372  win3D.setCameraZoom(win3D.getCameraZoom() / 1.2);
373  win3D.repaint();
374  break;
375  case '2':
376  gl_2d_scan->setVisibility(!gl_2d_scan->isVisible());
377  break;
378  case '3':
379  gl_points->setVisibility(!gl_points->isVisible());
380  break;
381  case 'F':
382  case 'f':
383  gl_frustum->setVisibility(!gl_frustum->isVisible());
384  break;
385  case '+':
386  gl_frustum->setVertFOV(gl_frustum->getVertFOV() + 1);
387  break;
388  case '-':
389  gl_frustum->setVertFOV(gl_frustum->getVertFOV() - 1);
390  break;
391  // ...and the rest in the kinect thread:
392  default:
393  thrPar.pushed_key = key;
394  break;
395  };
396  }
397 
398  std::this_thread::sleep_for(1ms);
399  }
400 
401  cout << "Waiting for grabbing thread to exit...\n";
402  thrPar.quit = true;
403  thHandle.join();
404  cout << "Bye!\n";
405 }
406 
407 int main(int argc, char** argv)
408 {
409  try
410  {
411  Test_Kinect();
412 
413  std::this_thread::sleep_for(50ms);
414  return 0;
415  }
416  catch (const std::exception& e)
417  {
418  std::cerr << "MRPT error: " << mrpt::exception_to_str(e) << std::endl;
419  return -1;
420  }
421  catch (...)
422  {
423  printf("Another exception!!");
424  return -1;
425  }
426 }
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:86
static Ptr Create(Args &&... args)
static Ptr Create(Args &&... args)
GLenum GLint ref
Definition: glext.h:4062
double DEG2RAD(const double x)
Degrees to radians.
This class allows loading and storing values and vectors of different types from ".ini" files easily.
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:128
A high-performance stopwatch, with typical resolution of nanoseconds.
CObservationIMU::Ptr new_obs_imu
Contains classes for various device interfaces.
y-axis acceleration (local/vehicle frame) (m/sec2)
STL namespace.
z-axis acceleration (local/vehicle frame) (m/sec2)
const float vert_FOV
volatile bool quit
In/Out variable: Forces the thread to exit or indicates an error in the thread that caused it to end...
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
Definition: CKinect.h:265
This base provides a set of functions for maths stuff.
GLint GLvoid * img
Definition: glext.h:3769
Used in CObservation3DRangeScan::convertTo2DScan()
This namespace contains representation of robot actions and observations.
void initialize() override
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
Definition: CKinect.cpp:134
static Ptr Create(Args &&... args)
Definition: CFrustum.h:53
void loadConfig(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
Loads the generic settings common to any sensor (See CGenericSensor), then call to "loadConfig_sensor...
void Test_Kinect()
GLsizei const GLchar ** string
Definition: glext.h:4116
void getNextObservation(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Definition: CKinect.cpp:504
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
CSetOfObjects::Ptr CornerXYZ(float scale=1.0)
Returns three arrows representing a X,Y,Z 3D corner.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
void thread_grabbing(TThreadParam &p)
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
A RGB color - floats in the range [0,1].
Definition: TColor.h:77
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
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
CObservation3DRangeScan::Ptr new_obs
RGB+D (+ optionally, 3D point cloud)
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:75
renders glyphs as filled polygons
Definition: opengl_fonts.h:35
This template class provides the basic functionality for a general 2D any-size, resizable container o...
GLfloat GLfloat p
Definition: glext.h:6398
x-axis acceleration (local/vehicle frame) (m/sec2)
static Ptr Create(Args &&... args)
Definition: CGridPlaneXY.h:31
volatile double Hz
Out variable: Approx.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:43
bool takeIntoAccountSensorPoseOnRobot
(Default: false) If false, local (sensor-centric) coordinates of points are generated.
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:147
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019