MRPT  1.9.9
COpenNI2Generic.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "hwdrivers-precomp.h" // Precompiled header
11 
15 
16 // Universal include for all versions of OpenCV
17 #include <mrpt/otherlibs/do_opencv_includes.h>
18 
19 #include <thread>
20 #include <mutex>
21 #include <atomic>
22 
23 #if MRPT_HAS_OPENNI2
24 
25 // This seems to be assumed by OpenNI.h and undefined for some reason in
26 // GCC/Ubuntu
27 #if !defined(_WIN32)
28 #define linux 1
29 #endif
30 
31 #include <OpenNI.h>
32 #include <PS1080.h>
33 #endif
34 
35 using namespace mrpt::hwdrivers;
36 using namespace mrpt::system;
37 using namespace mrpt::obs;
38 using namespace std;
39 
40 // Initialize static member
41 std::vector<std::shared_ptr<COpenNI2Generic::CDevice>> vDevices;
42 std::recursive_mutex vDevices_mx;
43 std::atomic<int> numInstances(0);
44 
45 #if MRPT_HAS_OPENNI2
46 bool setONI2StreamMode(
47  openni::VideoStream& stream, int w, int h, int fps,
48  openni::PixelFormat format);
49 std::string oni2DevInfoStr(const openni::DeviceInfo& info, int tab = 0);
50 bool cmpONI2Device(const openni::DeviceInfo& i1, const openni::DeviceInfo& i2);
51 #endif // MRPT_HAS_OPENNI2
52 
54 
56 {
57  return numInstances; // get atomic
58 }
59 
60 /*-------------------------------------------------------------
61 ctor
62 -------------------------------------------------------------*/
64  : m_width(640),
65  m_height(480),
66  m_fps(30.0f),
67 #if MRPT_HAS_OPENNI2
68  m_rgb_format(openni::PIXEL_FORMAT_RGB888),
69  m_depth_format(openni::PIXEL_FORMAT_DEPTH_1_MM),
70 #endif // MRPT_HAS_OPENNI2
71  m_verbose(false),
72  m_grab_image(true),
73  m_grab_depth(true),
74  m_grab_3D_points(true)
75 {
76  const char* sVerbose = getenv("MRPT_HWDRIVERS_VERBOSE");
77  m_verbose = (sVerbose != nullptr) && atoi(sVerbose) != 0;
78  // Start automatically:
79  if (!this->start())
80  {
81 #if MRPT_HAS_OPENNI2
83  "After initialization:\n %s\n", openni::OpenNI::getExtendedError()))
84 #endif
85  }
86 }
87 
89  int width, int height, float fps, bool open_streams_now)
90  : m_width(width),
91  m_height(height),
92  m_fps(fps),
93 #if MRPT_HAS_OPENNI2
94  m_rgb_format(openni::PIXEL_FORMAT_RGB888),
95  m_depth_format(openni::PIXEL_FORMAT_DEPTH_1_MM),
96 #endif // MRPT_HAS_OPENNI2
97  m_verbose(false),
98  m_grab_image(true),
99  m_grab_depth(true),
100  m_grab_3D_points(true)
101 {
102  const char* sVerbose = getenv("MRPT_HWDRIVERS_VERBOSE");
103  m_verbose = (sVerbose != nullptr) && atoi(sVerbose) != 0;
104  // Open?
105  if (open_streams_now)
106  {
107  if (!this->start())
108  {
109 #if MRPT_HAS_OPENNI2
111  "After initialization:\n %s\n",
112  openni::OpenNI::getExtendedError()))
113 #endif
114  }
115  }
116 }
117 
119 {
120 #if MRPT_HAS_OPENNI2
121  if (numInstances == 0)
122  {
123  if (openni::OpenNI::initialize() != openni::STATUS_OK)
124  {
125  return false;
126  }
127  else
128  {
129  std::cerr << "[" << __FUNCTION__ << "]" << std::endl
130  << " Initialized OpenNI2." << std::endl;
131  }
132  }
133  numInstances++;
134  return true;
135 #else
136  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
137 #endif // MRPT_HAS_OPENNI2
138 }
139 
140 /*-------------------------------------------------------------
141 dtor
142 -------------------------------------------------------------*/
144 {
145  numInstances--;
146  if (numInstances == 0)
147  {
148  kill();
149  }
150 }
151 
153 {
154  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
155  return vDevices.size();
156 }
157 void COpenNI2Generic::setVerbose(bool verbose) { m_verbose = verbose; }
158 bool COpenNI2Generic::isVerbose() const { return m_verbose; }
159 void COpenNI2Generic::showLog(const std::string& message) const
160 {
161  if (isVerbose() == false)
162  {
163  return;
164  }
165  std::cerr << message;
166 }
167 /** This method can or cannot be implemented in the derived class, depending on
168  * the need for it.
169  * \exception This method must throw an exception with a descriptive message if
170  * some critical error is found.
171  */
173 {
174 #if MRPT_HAS_OPENNI2
175  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
176  // Get devices list
177  openni::Array<openni::DeviceInfo> oni2InfoArray;
178  openni::OpenNI::enumerateDevices(&oni2InfoArray);
179 
180  const size_t numDevices = oni2InfoArray.getSize();
181  showLog(mrpt::format("[%s]\n", __FUNCTION__));
183  " Get device list. %d devices connected.\n", (int)numDevices));
184 
185  // Search new devices.
186  std::set<int> newDevices;
187  for (unsigned i = 0; i < numDevices; i++)
188  {
189  const openni::DeviceInfo& info = oni2InfoArray[i];
190  showLog(mrpt::format(" Device[%d]\n", i));
191  showLog(oni2DevInfoStr(info, 3) + "\n");
192 
193  bool isExist = false;
194  for (unsigned int j = 0, j_end = vDevices.size();
195  j < j_end && isExist == false; ++j)
196  {
197  if (cmpONI2Device(info, vDevices[j]->getInfo()))
198  {
199  isExist = true;
200  }
201  }
202  if (isExist == false)
203  {
204  newDevices.insert(i);
205  }
206  }
207  // Add new devices to device list(static member).
208  for (std::set<int>::const_iterator it = newDevices.begin(),
209  it_end = newDevices.end();
210  it != it_end; ++it)
211  {
212  const openni::DeviceInfo& info = oni2InfoArray[*it];
213  CDevice::Ptr device = CDevice::create(
214  info, (openni::PixelFormat)m_rgb_format,
215  (openni::PixelFormat)m_depth_format, m_verbose);
216  vDevices.push_back(device);
217  {
218  unsigned int sn;
219  if (device->getSerialNumber(sn))
220  {
221  showLog(
222  mrpt::format("Device[%d]: serial number: `%u`\n", *it, sn));
223  }
224  }
225  }
226 
227  if (getNumDevices() == 0)
228  {
229  showLog(" No devices connected -> EXIT\n");
230  }
231  else
232  {
233  showLog(mrpt::format(" %d devices were found.\n", getNumDevices()));
234  }
235  return getNumDevices();
236 #else
237  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
238 #endif // MRPT_HAS_OPENNI2
239 }
240 
242 {
243  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
244 #if MRPT_HAS_OPENNI2
245  vDevices.clear();
246  openni::OpenNI::shutdown();
247 #else
248  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
249 #endif // MRPT_HAS_OPENNI2
250 }
251 
252 bool COpenNI2Generic::isOpen(const unsigned sensor_id) const
253 {
254 #if MRPT_HAS_OPENNI2
255  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
256  if ((int)sensor_id >= getNumDevices())
257  {
258  return false;
259  }
260  return vDevices[sensor_id]->isOpen();
261 #else
262  MRPT_UNUSED_PARAM(sensor_id);
263  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
264 #endif // MRPT_HAS_OPENNI2
265 }
266 
267 void COpenNI2Generic::open(unsigned sensor_id)
268 {
269 #if MRPT_HAS_OPENNI2
270  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
271  // Sensor index validation.
272  if (!getNumDevices())
273  {
274  THROW_EXCEPTION("No OpenNI2 devices found.");
275  }
276  if ((int)sensor_id >= getNumDevices())
277  {
279  "Sensor index is higher than the number of connected devices.")
280  }
281  showLog(mrpt::format("[%s]\n", __FUNCTION__));
282  showLog(mrpt::format(" open[%d] ...\n", sensor_id));
283 
284  if (isOpen(sensor_id))
285  {
286  showLog(
287  mrpt::format(" The sensor [%d] is already opened\n", sensor_id));
288  return;
289  }
290  if (m_verbose)
291  printf(
292  "[COpenNI2Generic] DBG: [%s] about to call vDevices[%d]->open()\n",
293  __FUNCTION__, sensor_id);
294  vDevices[sensor_id]->open(m_width, m_height, m_fps);
295  showLog(vDevices[sensor_id]->getLog() + "\n");
296  showLog(mrpt::format(" Device [%d] ", sensor_id));
297  if (vDevices[sensor_id]->isOpen())
298  {
299  showLog(" open successfully.\n");
300  }
301  else
302  {
303  showLog(" open failed.\n");
304  }
305  std::this_thread::sleep_for(1000ms); // Sleep
306 #else
307  MRPT_UNUSED_PARAM(sensor_id);
308  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
309 #endif // MRPT_HAS_OPENNI2
310 }
311 
313  const std::set<unsigned>& serial_required)
314 {
315 #if MRPT_HAS_OPENNI2
316  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
317  showLog(mrpt::format("[%s]\n", __FUNCTION__));
318  unsigned num_open_dev = 0;
319  for (unsigned sensor_id = 0; sensor_id < vDevices.size(); sensor_id++)
320  {
321  unsigned int serialNum;
322  if (vDevices[sensor_id]->getSerialNumber(serialNum) == false)
323  {
324  showLog(vDevices[sensor_id]->getLog());
325  continue;
326  }
327  if (m_verbose)
328  printf(
329  "[COpenNI2Generic::openDevicesBySerialNum] checking device "
330  "with serial '%d'\n",
331  serialNum);
332 
333  if (serial_required.find(serialNum) == serial_required.end())
334  {
335  vDevices[sensor_id]->close();
336  continue;
337  }
338  if (vDevices[sensor_id]->isOpen())
339  {
340  num_open_dev++;
341  continue;
342  }
343  int width = m_width;
344  int height = m_height;
345  if (m_verbose)
346  printf(
347  "[COpenNI2Generic] DBG: [%s] about to call "
348  "vDevices[%d]->open(%d,%d,%d)\n",
349  __FUNCTION__, sensor_id, width, height, (int)m_fps);
350  if (vDevices[sensor_id]->open(width, height, m_fps) == false)
351  {
352  showLog(vDevices[sensor_id]->getLog());
353  continue;
354  }
355  num_open_dev++;
356  if (m_verbose)
357  printf(
358  "[COpenNI2Generic] DBG: [%s] now has %d devices open\n",
359  __FUNCTION__, num_open_dev);
360  }
361  return num_open_dev;
362 #else
363  MRPT_UNUSED_PARAM(serial_required);
364  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
365 #endif // MRPT_HAS_OPENNI2
366 }
367 
369  const unsigned int SerialRequired)
370 {
371  std::set<unsigned> serial_required;
372  serial_required.insert(SerialRequired);
373  return openDevicesBySerialNum(serial_required);
374 }
375 
377  const unsigned int SerialRequired, int& sensor_id) const
378 {
379 #if MRPT_HAS_OPENNI2
380  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
381  for (size_t i = 0, i_end = vDevices.size(); i < i_end; ++i)
382  {
383  unsigned int sn;
384  if (vDevices[i]->getSerialNumber(sn) == false)
385  {
386  continue;
387  }
388  if (sn == SerialRequired)
389  {
390  sensor_id = (int)i;
391  return true;
392  }
393  }
394  return false;
395 #else
396  MRPT_UNUSED_PARAM(SerialRequired);
397  MRPT_UNUSED_PARAM(sensor_id);
398  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
399 #endif // MRPT_HAS_OPENNI2
400 }
401 
402 void COpenNI2Generic::close(unsigned sensor_id)
403 {
404 #if MRPT_HAS_OPENNI2
405  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
406  // Sensor index validation.
407  if (!getNumDevices())
408  {
409  THROW_EXCEPTION("No OpenNI2 devices found.");
410  }
411  if ((int)sensor_id >= getNumDevices())
412  {
414  "Sensor index is higher than the number of connected devices.")
415  }
416  vDevices[sensor_id]->close();
417 #else
418  MRPT_UNUSED_PARAM(sensor_id);
419  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
420 #endif // MRPT_HAS_OPENNI2
421 }
422 
423 /** The main data retrieving function, to be called after calling loadConfig()
424  * and initialize().
425  * \param out_obs The output retrieved observation (only if there_is_obs=true).
426  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
427  * \param there_is_obs If set to false, there was no new observation.
428  * \param hardware_error True on hardware/comms error.
429  * \param sensor_id The index of the sensor accessed.
430  *
431  */
433  mrpt::img::CImage& rgb_img, mrpt::system::TTimeStamp& timestamp,
434  bool& there_is_obs, bool& hardware_error, unsigned sensor_id)
435 {
436 #if MRPT_HAS_OPENNI2
437  // Sensor index validation.
438  if (!getNumDevices())
439  {
440  THROW_EXCEPTION("No OpenNI2 devices found.");
441  }
442  if ((int)sensor_id >= getNumDevices())
443  {
445  "Sensor index is higher than the number of connected devices.")
446  }
447  if (vDevices[sensor_id]->getNextFrameRGB(
448  rgb_img, timestamp, there_is_obs, hardware_error) == false)
449  {
450  showLog(mrpt::format("[%s]\n", __FUNCTION__));
451  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
452  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
453  }
454 #else
455  MRPT_UNUSED_PARAM(rgb_img);
456  MRPT_UNUSED_PARAM(timestamp);
457  MRPT_UNUSED_PARAM(there_is_obs);
458  MRPT_UNUSED_PARAM(hardware_error);
459  MRPT_UNUSED_PARAM(sensor_id);
460  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
461 #endif // MRPT_HAS_OPENNI2
462 }
463 
464 /** The main data retrieving function, to be called after calling loadConfig()
465  * and initialize().
466  * \param depth_img The output retrieved depth image (only if
467  * there_is_obs=true).
468  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
469  * \param there_is_obs If set to false, there was no new observation.
470  * \param hardware_error True on hardware/comms error.
471  * \param sensor_id The index of the sensor accessed.
472  *
473  */
475  mrpt::math::CMatrix& depth_img, mrpt::system::TTimeStamp& timestamp,
476  bool& there_is_obs, bool& hardware_error, unsigned sensor_id)
477 {
478 #if MRPT_HAS_OPENNI2
479  // Sensor index validation.
480  if (getNumDevices() == 0)
481  {
482  THROW_EXCEPTION("No OpenNI2 devices found.");
483  }
484  if ((int)sensor_id >= getNumDevices())
485  {
487  "Sensor index is higher than the number of connected devices.")
488  }
489  if (vDevices[sensor_id]->getNextFrameD(
490  depth_img, timestamp, there_is_obs, hardware_error) == false)
491  {
492  showLog(mrpt::format("[%s]\n", __FUNCTION__));
493  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
494  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
495  }
496 #else
497  MRPT_UNUSED_PARAM(depth_img);
498  MRPT_UNUSED_PARAM(timestamp);
499  MRPT_UNUSED_PARAM(there_is_obs);
500  MRPT_UNUSED_PARAM(hardware_error);
501  MRPT_UNUSED_PARAM(sensor_id);
502  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
503 #endif // MRPT_HAS_OPENNI2
504 }
505 
506 /** The main data retrieving function, to be called after calling loadConfig()
507  * and initialize().
508  * \param out_obs The output retrieved observation (only if there_is_obs=true).
509  * \param there_is_obs If set to false, there was no new observation.
510  * \param hardware_error True on hardware/comms error.
511  * \param sensor_id The index of the sensor accessed.
512  *
513  */
515  mrpt::obs::CObservation3DRangeScan& out_obs, bool& there_is_obs,
516  bool& hardware_error, unsigned sensor_id)
517 {
518 #if MRPT_HAS_OPENNI2
519  // Sensor index validation.
520  if (!getNumDevices())
521  {
522  THROW_EXCEPTION("No OpenNI2 devices found.");
523  }
524  if ((int)sensor_id >= getNumDevices())
525  {
527  "Sensor index is higher than the number of connected devices.")
528  }
529  if (vDevices[sensor_id]->getNextFrameRGBD(
530  out_obs, there_is_obs, hardware_error) == false)
531  {
532  showLog(mrpt::format("[%s]\n", __FUNCTION__));
533  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
534  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
535  }
536 #else
537  MRPT_UNUSED_PARAM(out_obs);
538  MRPT_UNUSED_PARAM(there_is_obs);
539  MRPT_UNUSED_PARAM(hardware_error);
540  MRPT_UNUSED_PARAM(sensor_id);
541  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
542 #endif // MRPT_HAS_OPENNI2
543 }
544 
546  mrpt::img::TCamera& param, unsigned sensor_id) const
547 {
548 #if MRPT_HAS_OPENNI2
549  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
550  if (isOpen(sensor_id) == false)
551  {
552  return false;
553  }
554  return vDevices[sensor_id]->getCameraParam(CDevice::COLOR_STREAM, param);
555 #else
557  MRPT_UNUSED_PARAM(sensor_id);
558  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
559 #endif // MRPT_HAS_OPENNI2
560 }
561 
563  mrpt::img::TCamera& param, unsigned sensor_id) const
564 {
565 #if MRPT_HAS_OPENNI2
566  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
567  if (isOpen(sensor_id) == false)
568  {
569  return false;
570  }
571  return vDevices[sensor_id]->getCameraParam(CDevice::DEPTH_STREAM, param);
572 #else
574  MRPT_UNUSED_PARAM(sensor_id);
575  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
576 #endif // MRPT_HAS_OPENNI2
577 }
578 
579 #if MRPT_HAS_OPENNI2
580 /*
581 void openni::VideoMode::setResolution()
582 Setter function for the resolution of this VideoMode. Application use of this
583 function is not recommended.
584 Instead, use SensorInfo::getSupportedVideoModes() to obtain a list of valid
585 video modes
586 
587 -- cited from OpenNI2 help. setResolution() is not recommended.
588 */
589 bool setONI2StreamMode(
590  openni::VideoStream& stream, int w, int h, int fps,
591  openni::PixelFormat format)
592 {
593  // std::cout << "[COpenNI2Generic] Ask mode: " << w << "x" << h << " " <<
594  // fps << " fps. format " << format << std::endl;
595  bool found = false;
596  const openni::Array<openni::VideoMode>& modes =
597  stream.getSensorInfo().getSupportedVideoModes();
598  for (int i = 0, i_end = modes.getSize(); i < i_end; ++i)
599  {
600  // if (m_verbose) std::cout << "[COpenNI2Generic] Mode: " <<
601  // modes[i].getResolutionX() << "x" << modes[i].getResolutionY() << " "
602  // << modes[i].getFps() << " fps. format " << modes[i].getPixelFormat()
603  // << std::endl;
604  if (modes[i].getResolutionX() != w)
605  {
606  continue;
607  }
608  if (modes[i].getResolutionY() != h)
609  {
610  continue;
611  }
612  if (modes[i].getFps() != fps)
613  {
614  continue;
615  }
616  if (modes[i].getPixelFormat() != format)
617  {
618  continue;
619  }
620  openni::Status rc = stream.setVideoMode(modes[i]);
621  if (rc != openni::STATUS_OK)
622  {
623  return false;
624  }
625  return true;
626  }
627  return false;
628 }
629 
630 std::string oni2DevInfoStr(const openni::DeviceInfo& info, int tab)
631 {
632  std::stringstream sst;
633  std::string space;
634  for (int i = 0; i < tab; ++i)
635  {
636  space += " ";
637  }
638  sst << space << "name=" << info.getName() << std::endl;
639  sst << space << "uri=" << info.getUri() << std::endl;
640  sst << space << "vendor=" << info.getVendor() << std::endl;
641  sst << space << "product=" << info.getUsbProductId();
642  return sst.str();
643 }
644 
645 bool cmpONI2Device(const openni::DeviceInfo& i1, const openni::DeviceInfo& i2)
646 {
647  return (strcmp(i1.getUri(), i2.getUri()) == 0);
648 }
649 //
650 COpenNI2Generic::CDevice::CDevice(
651  const openni::DeviceInfo& info, openni::PixelFormat rgb,
652  openni::PixelFormat depth, bool verbose)
653  : m_info(info), m_mirror(true), m_verbose(verbose)
654 {
655  m_streams[COLOR_STREAM] =
656  CStream::create(m_device, openni::SENSOR_COLOR, rgb, m_log, m_verbose);
657  m_streams[IR_STREAM] =
658  CStream::create(m_device, openni::SENSOR_IR, rgb, m_log, m_verbose);
659  m_streams[DEPTH_STREAM] = CStream::create(
660  m_device, openni::SENSOR_DEPTH, depth, m_log, m_verbose);
661 }
662 
663 COpenNI2Generic::CDevice::~CDevice() { close(); }
664 bool COpenNI2Generic::CDevice::synchMirrorMode()
665 {
666  m_mirror = false;
667  // Check whether both stream support mirroring.
668  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
669  {
670  if (!m_streams[i]) continue;
671  bool mirror_support;
672  try
673  {
674  mirror_support = m_streams[i]->isMirrorSupported();
675  }
676  catch (std::logic_error& e)
677  {
678  throw(e);
679  }
680  if (mirror_support == false)
681  {
682  m_log << "[" << __FUNCTION__ << "]" << std::endl;
683  m_log << " openni::STREAM_PROPERTY_MIRRORING is not supported on "
684  << m_streams[i]->getName() << "." << std::endl;
685  m_log << " We assume this is MS Kinect and taken images are "
686  "inverted to right and left."
687  << std::endl;
688  // In this case, getMirroringEnabled() method always returns false.
689  // So we cannot confirm whether the images are inverted or not.
690  m_mirror = true;
691  break;
692  }
693  }
694  // Set both stream to same mirror mode.
695  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
696  {
697  if (!m_streams[i]) continue;
698  if (m_streams[i]->isMirrorSupported() == false)
699  {
700  break;
701  }
702  if (m_streams[i]->setMirror(m_mirror) == false)
703  {
704  return false;
705  }
706  }
707  return true;
708 }
709 
710 bool COpenNI2Generic::CDevice::startStreams()
711 {
712  MRPT_START
713  int num_ok = 0;
714  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
715  {
716  if (!m_streams[i]) continue;
717  if (m_verbose)
718  printf(" [%s] calling m_streams[%d]->start()\n", __FUNCTION__, i);
719  if (m_streams[i]->start() == false)
720  {
721  if (m_verbose)
722  printf(
723  " [%s] m_streams[%d]->start() returned FALSE!\n",
724  __FUNCTION__, i);
725  }
726  else
727  {
728  num_ok++;
729  }
730  if (m_verbose)
731  printf(
732  " [%s] m_streams[%d]->start() returned TRUE\n", __FUNCTION__,
733  i);
734  }
735  if (m_verbose)
736  printf(
737  " [COpenNI2Generic::CDevice::startStreams()] %d streams were "
738  "started.\n",
739  num_ok);
740  return num_ok > 0;
741  MRPT_END
742 }
743 
744 bool COpenNI2Generic::CDevice::isOpen() const
745 {
746  return (m_streams[COLOR_STREAM] && m_streams[COLOR_STREAM]->isValid()) ||
747  (m_streams[DEPTH_STREAM] && m_streams[DEPTH_STREAM]->isValid());
748 }
749 
750 void COpenNI2Generic::CDevice::close()
751 {
752  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
753  {
754  if (!m_streams[i]) continue;
755  m_streams[i]->destroy();
756  }
757  m_device.close();
758 }
759 
760 bool COpenNI2Generic::CDevice::open(int w, int h, int fps)
761 {
762  MRPT_START
763  if (m_verbose)
764  printf(
765  " [COpenNI2Generic::CDevice::open()] Called with w=%i h=%i "
766  "fps=%i\n",
767  w, h, fps);
768  clearLog();
769  close();
770  openni::Status rc = m_device.open(getInfo().getUri());
771  if (rc != openni::STATUS_OK)
772  {
773  m_log << "[" << __FUNCTION__ << "]" << std::endl
774  << " Failed to open device " << getInfo().getUri() << " "
775  << openni::OpenNI::getExtendedError() << std::endl;
776  return false;
777  }
778  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
779  {
780  if (!m_streams[i]) continue;
781  if (m_verbose)
782  printf(" [%s] calling m_streams[%d]->open()\n", __FUNCTION__, i);
783 
784  if (m_streams[i]->open(w, h, fps) == false)
785  {
786  if (m_verbose)
787  printf(
788  " [%s] m_streams[%d]->open() returned FALSE\n",
789  __FUNCTION__, i);
790  return false;
791  }
792  if (m_verbose)
793  printf(
794  " [%s] m_streams[%d]->open() returned OK\n", __FUNCTION__, i);
795  }
796 
797  if (synchMirrorMode() == false)
798  {
799  close();
800  return false;
801  }
802 
803  if (m_streams[DEPTH_STREAM])
804  {
805  int CloseRange = 0;
806  m_streams[DEPTH_STREAM]->setCloseRange(CloseRange);
807  m_log << " Close range: " << (CloseRange ? "On" : "Off") << std::endl;
808  }
809 
810  if (m_verbose)
811  printf(" DBG: checking if imageRegistrationMode is supported\n");
812  if (m_device.isImageRegistrationModeSupported(
813  openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR) &&
814  m_streams[DEPTH_STREAM] && m_streams[DEPTH_STREAM]->isValid() &&
815  m_streams[COLOR_STREAM] && m_streams[COLOR_STREAM]->isValid())
816  {
817  // SEB
818  // if(m_device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF)
819  // != openni::STATUS_OK){
820  if (m_device.setImageRegistrationMode(
821  openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR) != openni::STATUS_OK)
822  {
823  m_log << " setImageRegistrationMode() Failed:"
824  << openni::OpenNI::getExtendedError() << endl;
825  }
826  else
827  {
828  m_log << " setImageRegistrationMode() Success" << endl;
829  }
830  }
831  else
832  {
833  m_log << " Device doesn't do image registration!" << endl;
834  }
835 
836  if (0) // hasColor())
837  { // printf("DBG: hasColor() returned TRUE\n");
838  m_streams[COLOR_STREAM]->disableAutoExposure();
839  printf("DBG: returned from disableAutoExposure()\n");
840  }
841 
842  if (startStreams() == false)
843  {
844  close();
845  return false;
846  }
847  return true;
848  MRPT_END
849 }
850 
851 bool COpenNI2Generic::CDevice::getNextFrameRGB(
853  bool& there_is_obs, bool& hardware_error)
854 {
855  MRPT_START
856  if (!hasColor())
857  {
858  THROW_EXCEPTION("This OpenNI2 device does not support color imaging");
859  }
860  openni::VideoFrameRef frame;
861  if (m_streams[COLOR_STREAM]->getFrame(
862  frame, timestamp, there_is_obs, hardware_error) == false)
863  {
864  return false;
865  }
866  copyFrame<openni::RGB888Pixel, mrpt::img::CImage>(frame, img);
867 
868  return true;
869  MRPT_END
870 }
871 
872 bool COpenNI2Generic::CDevice::getNextFrameD(
874  bool& there_is_obs, bool& hardware_error)
875 {
876  MRPT_START
877  if (!hasDepth())
878  {
879  THROW_EXCEPTION("This OpenNI2 device does not support depth imaging");
880  }
881  openni::VideoFrameRef frame;
882  if (m_streams[DEPTH_STREAM]->getFrame(
883  frame, timestamp, there_is_obs, hardware_error) == false)
884  {
885  return false;
886  }
887  copyFrame<openni::DepthPixel, mrpt::math::CMatrix>(frame, img);
888 
889  return true;
890  MRPT_END
891 }
892 
893 bool COpenNI2Generic::CDevice::getNextFrameRGBD(
894  mrpt::obs::CObservation3DRangeScan& obs, bool& there_is_obs,
895  bool& hardware_error)
896 {
897  MRPT_START
898  clearLog();
899  there_is_obs = false;
900  hardware_error = false;
901 
902  if (!hasColor())
903  {
904  THROW_EXCEPTION("This OpenNI2 device does not support color imaging");
905  }
906  if (!hasDepth())
907  {
908  THROW_EXCEPTION("This OpenNI2 device does not support depth imaging");
909  }
910  // Read a frame (depth + rgb)
912  openni::VideoFrameRef frame[STREAM_TYPE_SIZE];
913  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
914  {
915  if (!m_streams[i] || !m_streams[i]->isValid()) continue;
916  if (m_streams[i]->getFrame(
917  frame[i], tm, there_is_obs, hardware_error) == false)
918  {
919  return false;
920  }
921  if (there_is_obs == false || hardware_error == true)
922  {
923  return false;
924  }
925  }
926 
927  const int width = frame[COLOR_STREAM].getWidth();
928  const int height = frame[COLOR_STREAM].getHeight();
929  if ((frame[DEPTH_STREAM].getWidth() != width) ||
930  (frame[DEPTH_STREAM].getHeight() != height))
931  {
932  m_log << "[" << __FUNCTION__ << "]" << std::endl
933  << " Both frames don't have the same size." << std::endl;
934  return false;
935  }
936  there_is_obs = true;
937  obs.hasConfidenceImage = false;
938  obs.hasIntensityImage = true;
939  obs.hasRangeImage = true;
940  obs.range_is_depth = true;
941  obs.hasPoints3D = false;
943  resize(obs, width, height);
944 
945  const char* data[STREAM_TYPE_SIZE] = {
946  (const char*)frame[COLOR_STREAM].getData(),
947  (const char*)frame[DEPTH_STREAM].getData()};
948  const int step[STREAM_TYPE_SIZE] = {frame[COLOR_STREAM].getStrideInBytes(),
949  frame[DEPTH_STREAM].getStrideInBytes()};
950 
951  for (int yc = 0; yc < height; ++yc)
952  {
953  const openni::RGB888Pixel* pRgb =
954  (const openni::RGB888Pixel*)data[COLOR_STREAM];
955  const openni::DepthPixel* pDepth =
956  (const openni::DepthPixel*)data[DEPTH_STREAM];
957  for (int xc = 0; xc < width; ++xc, ++pDepth, ++pRgb)
958  {
959  int x = xc;
960  if (isMirrorMode())
961  {
962  x = width - x - 1;
963  }
964  setPixel(*pRgb, obs.intensityImage, x, yc);
965  setPixel(*pDepth, obs.rangeImage, x, yc);
966  }
967  data[COLOR_STREAM] += step[COLOR_STREAM];
968  data[DEPTH_STREAM] += step[DEPTH_STREAM];
969  }
970 
971  return true;
972  MRPT_END
973 }
974 
975 COpenNI2Generic::CDevice::Ptr COpenNI2Generic::CDevice::create(
976  const openni::DeviceInfo& info, openni::PixelFormat rgb,
977  openni::PixelFormat depth, bool verbose)
978 {
979  return Ptr(new CDevice(info, rgb, depth, verbose));
980 }
981 
982 bool COpenNI2Generic::CDevice::getSerialNumber(std::string& sn)
983 {
984  clearLog();
985  openni::Status rc;
986  bool isOpened = isOpen();
987  if (isOpened == false)
988  {
989  rc = m_device.open(getInfo().getUri());
990  if (rc != openni::STATUS_OK)
991  {
992  m_log << "[" << __FUNCTION__ << "]" << std::endl
993  << " Failed to open device " << getInfo().getUri() << " "
994  << openni::OpenNI::getExtendedError() << std::endl;
995  return false;
996  }
997  }
998  char serialNumber[16];
999  rc = m_device.getProperty(ONI_DEVICE_PROPERTY_SERIAL_NUMBER, &serialNumber);
1000  if (rc != openni::STATUS_OK)
1001  {
1002  m_log << "[" << __FUNCTION__ << "]" << std::endl
1003  << " Failed to getProperty(ONI_DEVICE_PROPERTY_SERIAL_NUMBER) "
1004  << getInfo().getUri() << " " << openni::OpenNI::getExtendedError()
1005  << std::endl;
1006  return false;
1007  }
1008  sn = std::string(serialNumber);
1009  if (isOpened == false)
1010  {
1011  m_device.close();
1012  }
1013  return true;
1014 }
1015 
1016 bool COpenNI2Generic::CDevice::getSerialNumber(unsigned int& sn)
1017 {
1018  std::string str;
1019  if (getSerialNumber(str) == false)
1020  {
1021  return false;
1022  }
1023  std::stringstream sst;
1024  sst.str(str);
1025  sst >> sn;
1026  return !sst.fail();
1027 }
1028 //
1030  openni::Device& device, openni::SensorType type, openni::PixelFormat format,
1031  std::ostream& log, bool verbose)
1032  : m_log(log),
1033  m_device(device),
1034  m_strName("Unknown"),
1035  m_type(type),
1036  m_format(format),
1037  m_verbose(verbose)
1038 {
1039  if (m_type == openni::SENSOR_COLOR)
1040  {
1041  m_strName = "openni::SENSOR_COLOR";
1042  }
1043  else if (m_type == openni::SENSOR_DEPTH)
1044  {
1045  m_strName = "openni::SENSOR_DEPTH";
1046  }
1047  else if (m_type == openni::SENSOR_IR)
1048  {
1049  m_strName = "openni::SENSOR_IR";
1050  }
1051  else
1052  {
1053  m_log << "[" << __FUNCTION__ << "]" << std::endl
1054  << " Unknown SensorType -> " << m_type << std::endl;
1055  }
1056 }
1057 
1058 COpenNI2Generic::CDevice::CStream::~CStream() { destroy(); }
1059 bool COpenNI2Generic::CDevice::CStream::isMirrorSupported() const
1060 {
1061  if (isValid() == false)
1062  {
1063  THROW_EXCEPTION(getName() + " is not opened.");
1064  }
1065  return m_stream.isPropertySupported(openni::STREAM_PROPERTY_MIRRORING);
1066 }
1067 
1068 bool COpenNI2Generic::CDevice::CStream::setMirror(bool flag)
1069 {
1070  if (isValid() == false)
1071  {
1072  m_log << "[" << __FUNCTION__ << "]" << std::endl
1073  << " " << getName() << " is not opened." << std::endl;
1074  return false;
1075  }
1076  if (m_stream.isPropertySupported(openni::STREAM_PROPERTY_MIRRORING) ==
1077  false)
1078  {
1079  return false;
1080  }
1081  if (m_stream.setMirroringEnabled(flag) != openni::STATUS_OK)
1082  {
1083  m_log << "[" << __FUNCTION__ << "]" << std::endl
1084  << " setMirroringEnabled() failed: "
1085  << openni::OpenNI::getExtendedError() << std::endl;
1086  return false;
1087  }
1088  return true;
1089 }
1090 
1091 bool COpenNI2Generic::CDevice::CStream::isValid() const
1092 {
1093  return m_stream.isValid();
1094 }
1095 
1096 void COpenNI2Generic::CDevice::CStream::destroy() { m_stream.destroy(); }
1097 void COpenNI2Generic::CDevice::CStream::setCloseRange(int& value)
1098 {
1099  if (m_verbose)
1100  printf(
1101  " [CDevice::CStream::setCloseRange] entry with value=%d\n",
1102  value);
1103  m_stream.setProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, value);
1104  if (m_verbose)
1105  printf(
1106  " [CDevice::CStream::setCloseRange] returned from "
1107  "mstream.setProperty()\n");
1108  m_stream.getProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, &value);
1109  if (m_verbose)
1110  printf(
1111  " [CDevice::CStream::setCloseRange] returned from "
1112  "mstream.getProperty() ... value %d\n",
1113  value);
1114 }
1115 
1116 bool COpenNI2Generic::CDevice::CStream::open(int w, int h, int fps)
1117 {
1118  destroy();
1119  if (m_type != openni::SENSOR_COLOR && m_type != openni::SENSOR_DEPTH &&
1120  m_type != openni::SENSOR_IR)
1121  { // SEB added IR
1122  m_log << "[" << __FUNCTION__ << "]" << std::endl
1123  << " Unknown SensorType -> " << m_type << std::endl;
1124  return false;
1125  }
1126  if (m_verbose)
1127  printf(
1128  " [COpenNI2Generic::CDevice::CStream::open] opening sensor "
1129  "stream with m_type == %d\n",
1130  (int)m_type);
1131  openni::Status rc = openni::STATUS_OK;
1132  // if(m_type == openni::SENSOR_COLOR) {
1133  // m_type = openni::SENSOR_IR;
1134  // m_strName="openni::SENSOR_IR"; // SEB added
1135  // if (m_verbose) printf("DBG: changing type to SENSOR_IR
1136  //(%d)\n",(int)m_type);
1137  // } // added whole if stmt
1138  rc = m_stream.create(m_device, m_type);
1139  if (rc != openni::STATUS_OK)
1140  {
1141  m_log << "[" << __FUNCTION__ << "]" << std::endl
1142  << " Couldn't find sensor " << m_strName << ":"
1143  << openni::OpenNI::getExtendedError() << std::endl;
1144  if (m_type == openni::SENSOR_COLOR)
1145  {
1146  m_type = openni::SENSOR_IR;
1147  m_strName = "openni::SENSOR_IR"; // SEB added
1148  if (m_verbose)
1149  printf("DBG: changing type to SENSOR_IR (%d)\n", (int)m_type);
1150  rc = m_stream.create(m_device, m_type);
1151  } // SEB added whole if stmt
1152  else
1153  return false;
1154  }
1155  if (m_verbose) printf("returned OK from stream.create()\n");
1156  openni::VideoMode options = m_stream.getVideoMode();
1157  m_log << "[" << __FUNCTION__ << "]" << std::endl;
1158  m_log << " " << m_strName << std::endl;
1159  m_log << " "
1160  << mrpt::format(
1161  "Initial resolution (%d, %d) FPS %d Format %d",
1162  options.getResolutionX(), options.getResolutionY(),
1163  options.getFps(), options.getPixelFormat())
1164  << std::endl;
1165  if (m_verbose) printf("DBG: calling setONI2StreamMode()\n");
1166  if (setONI2StreamMode(m_stream, w, h, fps, m_format) == false)
1167  {
1168  m_log << " Can't find desired mode in the " << getName() << std::endl;
1169  destroy();
1170  return false;
1171  }
1172  if (m_verbose) printf("DBG: returned OK from setONI2StreamMode()\n");
1173  if (m_verbose) printf("DBG: calling stream.getVideoMode()\n");
1174  options = m_stream.getVideoMode();
1175  m_log << " "
1176  << mrpt::format(
1177  "-> (%d, %d) FPS %d Format %d", options.getResolutionX(),
1178  options.getResolutionY(), options.getFps(),
1179  options.getPixelFormat())
1180  << std::endl;
1181  if (m_verbose)
1182  printf(
1183  " [COpenNI2Generic::CDevice::CStream::open] returning TRUE\n");
1184  return true;
1185 }
1186 
1188 {
1189  if (isValid() == false)
1190  {
1191  m_log << "[" << __FUNCTION__ << "]" << std::endl
1192  << " " << getName() << " is not opened." << std::endl;
1193  return false;
1194  }
1195  if (m_stream.start() != openni::STATUS_OK)
1196  {
1197  m_log << "[" << __FUNCTION__ << "]" << std::endl
1198  << " Couldn't start " << getName()
1199  << " stream:" << openni::OpenNI::getExtendedError() << std::endl;
1200  this->destroy();
1201  return false;
1202  }
1203  return true;
1204 }
1205 
1206 COpenNI2Generic::CDevice::CStream::Ptr
1207  COpenNI2Generic::CDevice::CStream::create(
1208  openni::Device& device, openni::SensorType type,
1209  openni::PixelFormat format, std::ostream& log, bool verbose)
1210 {
1211  return Ptr(new CStream(device, type, format, log, verbose));
1212 }
1213 
1214 bool COpenNI2Generic::CDevice::CStream::getFrame(
1215  openni::VideoFrameRef& frame, mrpt::system::TTimeStamp& timestamp,
1216  bool& there_is_obs, bool& hardware_error)
1217 {
1218  there_is_obs = false;
1219  hardware_error = false;
1220  if (isValid() == false)
1221  {
1222  return false;
1223  }
1224  openni::Status rc = m_stream.readFrame(&frame);
1225  if (rc != openni::STATUS_OK)
1226  {
1227  hardware_error = true;
1228  std::string message =
1229  mrpt::format("Failed to grab frame from %s", getName().c_str());
1230  THROW_EXCEPTION(message);
1231  }
1232  there_is_obs = true;
1233  timestamp = mrpt::system::getCurrentTime();
1234  return true;
1235 }
1236 
1237 #endif // MRPT_HAS_OPENNI2
#define MRPT_START
Definition: exceptions.h:262
int getNumDevices() const
The number of available devices at initialization.
bool getDepthSensorParam(mrpt::img::TCamera &param, unsigned sensor_id=0) const
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
mrpt::system::TTimeStamp getCurrentTime()
Returns the current (UTC) system time.
Definition: datetime.h:82
void getNextFrameRGB(mrpt::img::CImage &rgb_img, mrpt::system::TTimeStamp &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
void getNextFrameRGBD(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Contains classes for various device interfaces.
COpenNI2Generic()
Default ctor (width=640, height=480, fps=30)
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:3600
STL namespace.
mrpt::io::CStream CStream
Definition: utils/CStream.h:5
GLenum GLsizei width
Definition: glext.h:3531
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
int m_width
The same options (width, height and fps) are set for all the sensors.
void kill()
Kill the OpenNI2 driver.
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
std::vector< std::shared_ptr< COpenNI2Generic::CDevice > > vDevices
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:40
unsigned int openDeviceBySerial(const unsigned int SerialRequired)
Open a RGBD device specified by its serial number.
bool start()
Open all sensor streams (normally called automatically at constructor, no need to call it manually)...
bool getColorSensorParam(mrpt::img::TCamera &param, unsigned sensor_id=0) const
GLint GLvoid * img
Definition: glext.h:3763
bool isOpen(const unsigned sensor_id) const
Whether there is a working connection to the sensor.
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
static int getNumInstances()
Get the number of OpenNI2 cameras currently open via COpenNI2Generic.
This namespace contains representation of robot actions and observations.
void getNextFrameD(mrpt::math::CMatrix &depth_img, mrpt::system::TTimeStamp &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
bool hasRangeImage
true means the field rangeImage contains valid data
void close(unsigned sensor_id=0)
Close the connection to the sensor (no need to call it manually unless desired for some reason...
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:27
std::atomic< int > numInstances(0)
enum Status { eInsideTag=0, eOutsideTag } Status
Definition: xmlParser.cpp:804
bool hasPoints3D
true means the field points3D contains valid data.
GLsizei const GLchar ** string
Definition: glext.h:4101
unsigned int openDevicesBySerialNum(const std::set< unsigned > &vSerialRequired)
Open a set of RGBD devices specified by their serial number.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:60
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
bool hasIntensityImage
true means the field intensityImage contains valid data
#define MRPT_END
Definition: exceptions.h:266
std::recursive_mutex vDevices_mx
void open(unsigned sensor_id=0)
Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - us...
bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int &sensor_id) const
Get the ID of the device corresponding to &#39;SerialRequired&#39;.
GLenum GLsizei GLenum format
Definition: glext.h:3531
int getConnectedDevices()
Get a list of the connected OpenNI2 sensors.
GLsizei const GLfloat * value
Definition: glext.h:4117
void showLog(const std::string &message) const
GLenum GLint x
Definition: glext.h:3538
GLuint start
Definition: glext.h:3528
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:22
double getHeight(const TPolygon3D &p, const TPoint3D &c)
GLenum GLsizei GLsizei height
Definition: glext.h:3554
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
GLfloat param
Definition: glext.h:3831
GLsizei GLsizei GLenum GLenum const GLvoid * data
Definition: glext.h:3546
const Scalar * const_iterator
Definition: eigen_plugins.h:27
GLuint GLuint GLsizei GLenum type
Definition: glext.h:3528
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
bool hasConfidenceImage
true means the field confidenceImage contains valid data
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020