MRPT  1.9.9
CSwissRanger3DCamera.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 headers
11 
13 
15 #include <mrpt/system/filesystem.h>
16 
18 
19 #if MRPT_HAS_SWISSRANGE
20 #ifdef _WIN32
21 #define WIN32_LEAN_AND_MEAN
22 #include <windows.h>
23 #endif
24 
25 #include <libMesaSR.h>
26 
27 #ifdef MRPT_OS_LINUX
28 #include <termios.h>
29 #include <stdio.h>
30 #include <unistd.h>
31 
32 #include <linux/sockios.h>
33 #include <asm/ioctls.h>
34 #include <sys/select.h>
35 #endif
36 #endif
37 
38 using namespace mrpt::hwdrivers;
39 using namespace mrpt::system;
40 using namespace std;
41 
42 /*-------------------------------------------------------------
43  ctor
44  -------------------------------------------------------------*/
46  : m_sensorPoseOnRobot(),
47  m_save_3d(true),
48  m_save_range_img(true),
49  m_save_intensity_img(true),
50  m_save_confidence(false),
51 
52  m_enable_img_hist_equal(false),
53  m_enable_median_filter(true),
54  m_enable_mediancross_filter(false),
55  m_enable_conv_gray(false),
56  m_enable_denoise_anf(true),
57 
58  m_open_from_usb(true),
59  m_usb_serial(0),
60  m_ip_address("192.168.2.14"),
61  m_rows(0),
62  m_cols(0),
63  m_cam_serial_num(0),
64  m_maxRange(5),
65  m_preview_window(false)
66 {
67  m_sensorLabel = "3DCAM";
68 
69  // Default params: Obtained from a SR4000 with 0.004px avr reprojection
70  // error.
71  m_cameraParams.ncols = 176;
72  m_cameraParams.nrows = 144;
73  m_cameraParams.intrinsicParams(0, 0) = 262.9201; // fx
74  m_cameraParams.intrinsicParams(1, 1) = 262.9218; // fy
75  m_cameraParams.intrinsicParams(0, 2) = 87.99958; // cx
76  m_cameraParams.intrinsicParams(1, 2) = 68.99957; // cy
77  m_cameraParams.dist[0] = -8.258543e-01;
78  m_cameraParams.dist[1] = 6.561022e-01;
79  m_cameraParams.dist[2] = 2.699818e-06;
80  m_cameraParams.dist[3] = -3.263559e-05;
81  m_cameraParams.dist[4] = 0;
82 
83 #if !MRPT_HAS_SWISSRANGE
85  "MRPT was compiled without support for SwissRanger 3D cameras! Rebuild "
86  "it.")
87 #endif
88 }
89 
90 /*-------------------------------------------------------------
91  dtor
92  -------------------------------------------------------------*/
94 /*-------------------------------------------------------------
95  Modified A-law compression algorithm for uint16_t -> uint8_t
96  The original method uses signed int16_t. It's being tuned for
97  what we want here...
98  -------------------------------------------------------------*/
99 static char ALawCompressTable[128] = {
100  1, 1, 2, 2, 3, 3, 3, 3, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5,
101  5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6,
102  6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 7, 7,
103  7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7,
104  7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7,
105  7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7};
106 
108 bool table_16u_to_8u_init = false;
109 
110 unsigned char LinearToALawSample(uint16_t sample)
111 {
112  if (sample >= 0x200)
113  {
114  int exponent = ALawCompressTable[(sample >> 9) & 0x7F];
115  int mantissa = (sample >> (exponent + 3)) & 0x1F;
116  return ((exponent << 5) | mantissa);
117  }
118  else
119  {
120  return (sample >> 4);
121  }
122 }
123 
125 {
126  for (unsigned int i = 0; i < 0x10000; i++)
128 }
129 
130 /** This method can or cannot be implemented in the derived class, depending on
131  * the need for it.
132  * \exception This method must throw an exception with a descriptive message if
133  * some critical error is found.
134  */
136 {
137  if (!open()) THROW_EXCEPTION("Error opening SwissRanger 3D camera.");
138 }
139 
140 /** This method will be invoked at a minimum rate of "process_rate" (Hz)
141  * \exception This method must throw an exception with a descriptive message if
142  * some critical error is found.
143  */
145 {
146  using namespace mrpt::obs;
147 
148  bool thereIs, hwError;
149 
151  mrpt::make_aligned_shared<CObservation3DRangeScan>();
152 
153  getNextObservation(*newObs, thereIs, hwError);
154 
155  if (hwError)
156  {
157  m_state = ssError;
158  THROW_EXCEPTION("Couldn't communicate to the SwissRanger 3D camera!");
159  }
160 
161  if (thereIs)
162  {
163  m_state = ssWorking;
164 
165  appendObservation(newObs);
166  }
167 }
168 
169 /** Loads specific configuration for the device from a given source of
170  * configuration parameters, for example, an ".ini" file, loading from the
171  * section "[iniSection]" (see config::CConfigFileBase and derived classes)
172  * \exception This method must throw an exception with a descriptive message if
173  * some critical parameter is missing or has an invalid value.
174  */
176  const mrpt::config::CConfigFileBase& configSource,
177  const std::string& iniSection)
178 {
179  using mrpt::DEG2RAD;
180 
182  configSource.read_float(iniSection, "pose_x", 0),
183  configSource.read_float(iniSection, "pose_y", 0),
184  configSource.read_float(iniSection, "pose_z", 0),
185  DEG2RAD(configSource.read_float(iniSection, "pose_yaw", 0)),
186  DEG2RAD(configSource.read_float(iniSection, "pose_pitch", 0)),
187  DEG2RAD(configSource.read_float(iniSection, "pose_roll", 0)));
188 
190  configSource.read_bool(iniSection, "preview_window", m_preview_window);
191 
192  m_save_3d = configSource.read_bool(iniSection, "save_3d", m_save_3d);
194  configSource.read_bool(iniSection, "save_range_img", m_save_range_img);
195  m_save_intensity_img = configSource.read_bool(
196  iniSection, "save_intensity_img", m_save_intensity_img);
197  m_save_confidence = configSource.read_bool(
198  iniSection, "save_confidence", m_save_confidence);
199 
200  m_enable_img_hist_equal = configSource.read_bool(
201  iniSection, "enable_img_hist_equal", m_enable_img_hist_equal);
202  m_enable_median_filter = configSource.read_bool(
203  iniSection, "enable_median_filter", m_enable_median_filter);
204  m_enable_mediancross_filter = configSource.read_bool(
205  iniSection, "enable_mediancross_filter", m_enable_mediancross_filter);
206  m_enable_conv_gray = configSource.read_bool(
207  iniSection, "enable_conv_gray", m_enable_conv_gray);
208  m_enable_denoise_anf = configSource.read_bool(
209  iniSection, "enable_denoise_anf", m_enable_denoise_anf);
210 
212  configSource.read_bool(iniSection, "open_from_usb", m_open_from_usb);
213  m_usb_serial =
214  configSource.read_uint64_t(iniSection, "usb_serial", m_usb_serial);
215  m_ip_address =
216  configSource.read_string(iniSection, "ip_address", m_ip_address);
217 
219  iniSection, "external_images_format", m_external_images_format));
221  iniSection, "external_images_jpeg_quality",
223 
224  try
225  {
226  m_cameraParams.loadFromConfigFile(iniSection, configSource);
227  }
228  catch (std::exception&)
229  {
230  // If there's some missing field, just keep the default values.
231  }
232 }
233 
235 {
236 #if MRPT_HAS_SWISSRANGE
237  unsigned short version[4];
238  if (0 != SR_GetVersion(version)) return false;
239 
240  out_version =
241  format("%d.%d.%d.%d", version[3], version[2], version[1], version[0]);
242  return true;
243 #else
244  MRPT_UNUSED_PARAM(out_version);
245  return false;
246 #endif
247 }
248 
249 bool CSwissRanger3DCamera::isOpen() const { return m_cam != nullptr; }
251 {
252 #if MRPT_HAS_SWISSRANGE
253  if (isOpen()) close();
254 
255  SRCAM cam;
256  if (m_open_from_usb)
257  {
258  if (SR_OpenUSB(&cam, this->m_usb_serial) <= 0) return false;
259  }
260  else
261  {
262  if (SR_OpenETH(&cam, this->m_ip_address.c_str()) <= 0) return false;
263  }
264  m_cam = cam;
265 
266  // Initialization code:
267  m_rows = SR_GetRows(cam);
268  m_cols = SR_GetCols(cam);
269 
270  m_cam_serial_num = SR_ReadSerial(cam);
271 
272  // Deduce max range from frequency:
273  const ModulationFrq fr = SR_GetModulationFrequency(cam);
274  switch (fr)
275  {
276  case MF_40MHz:
277  m_maxRange = 3.75;
278  break;
279  case MF_30MHz:
280  m_maxRange = 5;
281  break;
282  case MF_21MHz:
283  m_maxRange = 7.14;
284  break;
285  case MF_20MHz:
286  m_maxRange = 7.5;
287  break;
288  case MF_19MHz:
289  m_maxRange = 7.89;
290  break;
291  case MF_60MHz:
292  m_maxRange = 2.5;
293  break;
294  case MF_15MHz:
295  m_maxRange = 10;
296  break;
297  case MF_10MHz:
298  m_maxRange = 15;
299  break;
300  case MF_29MHz:
301  m_maxRange = 5.17;
302  break;
303  case MF_31MHz:
304  m_maxRange = 4.84;
305  break;
306  case MF_14_5MHz:
307  m_maxRange = 10.34;
308  break;
309  case MF_15_5MHz:
310  m_maxRange = 9.68;
311  break;
312 
313  default:
314  m_maxRange = 5.0;
315  break;
316  }
317 
318  SR_SetTimeout(cam, 1000 /* ms */);
319 
321 
322  return true;
323 #else
324  return false;
325 #endif
326 }
327 
329 {
330 #if MRPT_HAS_SWISSRANGE
331  if (m_cam) SR_Close(SRCAM(m_cam));
332  m_cam = nullptr;
333 #endif
334 }
335 
337 {
338 #if MRPT_HAS_SWISSRANGE
339  if (!isOpen()) return;
340 
341  SR_SetMode(
342  SRCAM(m_cam),
343  AM_COR_FIX_PTRN | // turns on fix pattern noise correction <b>this
344  // should always be enabled for good distance
345  // measurement</b>
346  (m_enable_median_filter ? AM_MEDIAN : 0) |
347  (m_enable_conv_gray ? AM_CONV_GRAY : 0) |
348  (m_enable_denoise_anf ? AM_DENOISE_ANF : 0) |
349  (m_save_confidence ? AM_CONF_MAP : 0) |
350  (m_enable_mediancross_filter ? AM_MEDIANCROSS : 0));
351 #endif
352 }
353 
354 /** The main data retrieving function, to be called after calling loadConfig()
355  * and initialize().
356  * \param out_obs The output retrieved observation (only if
357  * there_is_obs=true).
358  * \param there_is_obs If set to false, there was no new observation.
359  * \param hardware_error True on hardware/comms error.
360  *
361  * \sa doProcess
362  */
364  mrpt::obs::CObservation3DRangeScan& _out_obs, bool& there_is_obs,
365  bool& hardware_error)
366 {
367  there_is_obs = false;
368  hardware_error = false;
369 #if MRPT_HAS_SWISSRANGE
370 
371  int bytesRx = SR_Acquire(SRCAM(m_cam));
372  if (!bytesRx)
373  {
374  cerr << "[CSwissRanger3DCamera] Zero bytes read from the camera."
375  << endl;
376  hardware_error = true;
377  return;
378  }
379 
380  // Extract images:
381  ImgEntry* imgEntryArray;
382  const int nImgs = SR_GetImageList(SRCAM(m_cam), &imgEntryArray);
383 
384  if (!nImgs)
385  {
386  cerr << "[CSwissRanger3DCamera] Error: no images in image list."
387  << endl;
388  hardware_error = true;
389  return;
390  }
391 
392  // Initialize the output observation:
396  obs.maxRange = m_maxRange;
397  obs.stdError = 0.01f;
398 
399  // Process each of the images:
400  for (int i = 0; i < nImgs; i++)
401  {
402  const ImgEntry* img = imgEntryArray + i;
403  switch (img->imgType)
404  {
405  // Ranges:
406  case ImgEntry::IT_DISTANCE:
407  {
408  if (this->m_save_range_img)
409  {
410  ASSERT_(img->dataType == ImgEntry::DT_USHORT)
411  obs.hasRangeImage = true;
412  obs.range_is_depth = false;
413 
414  // Convert data from uint16_t to float ranges:
415  // (0x0000, 0xFFFF) -> (0m, 5m)
416  const float K = obs.maxRange / 0xFFFF;
417  obs.rangeImage.setSize(img->height, img->width);
418 
419  const uint16_t* data_ptr =
420  reinterpret_cast<const uint16_t*>(img->data);
421 
422  for (size_t y = 0; y < img->height; y++)
423  for (size_t x = 0; x < img->width; x++)
424  obs.rangeImage.set_unsafe(y, x, K * (*data_ptr++));
425  }
426 
427  if (this->m_save_3d)
428  {
429  ASSERT_(img->dataType == ImgEntry::DT_USHORT)
430  obs.hasPoints3D = true;
431 
432  const size_t N = img->height * img->width;
433  obs.points3D_x.resize(N);
434  obs.points3D_y.resize(N);
435  obs.points3D_z.resize(N);
436 
437  // Swap XYZ order, so:
438  // SwissRange -> MRPT
439  // Z X
440  // X Y
441  // Y Z
442  SR_CoordTrfFlt(
443  SRCAM(m_cam),
444  &obs.points3D_y[0], // X
445  &obs.points3D_z[0], // Y
446  &obs.points3D_x[0], // Z
447  sizeof(float), sizeof(float), sizeof(float));
448  }
449  }
450  break;
451 
452  // Intensity:
453  case ImgEntry::IT_AMPLITUDE:
454  {
455  if (this->m_save_intensity_img)
456  {
457  ASSERT_(img->dataType == ImgEntry::DT_USHORT)
458  obs.hasIntensityImage = true;
459 
460  // Make sure the camera params are there:
461  m_cameraParams.scaleToResolution(img->width, img->height);
463 
464  // make sure the modified A-law Look Up Table is up-to-date:
466  {
467  table_16u_to_8u_init = true;
469  }
470 
471  obs.intensityImage.resize(img->width, img->height, 1, true);
472 
473  const uint16_t* data_ptr =
474  reinterpret_cast<const uint16_t*>(img->data);
475  for (size_t y = 0; y < img->height; y++)
476  {
477  uint8_t* row = obs.intensityImage.get_unsafe(0, y, 0);
478  for (size_t x = 0; x < img->width; x++)
479  // Convert 16u -> 8u
480  (*row++) = table_16u_to_8u[*data_ptr++];
481  }
482 
485 
486  // Save as external image file??
487  if (!m_path_for_external_images.empty())
488  {
489  const string filName =
491  format(
492  "_INT_%f.%s",
493  (double)timestampTotime_t(obs.timestamp),
494  m_external_images_format.c_str());
496  m_path_for_external_images + string("/") + filName,
498  obs.intensityImage.setExternalStorage(filName);
499  }
500  }
501  }
502  break;
503 
504  // Confidence:
505  case ImgEntry::IT_CONF_MAP:
506  {
507  if (this->m_save_confidence)
508  {
509  ASSERT_(img->dataType == ImgEntry::DT_USHORT)
510  obs.hasConfidenceImage = true;
511 
513  img->width, img->height, 1, true);
514 
515  const uint16_t* data_ptr =
516  reinterpret_cast<const uint16_t*>(img->data);
517  for (size_t y = 0; y < img->height; y++)
518  {
519  uint8_t* row = obs.confidenceImage.get_unsafe(0, y, 0);
520  for (size_t x = 0; x < img->width; x++)
521  (*row++) = (*data_ptr++) >> 8; // Convert 16u -> 8u
522  }
523 
524  // Save as external image file??
525  if (!m_path_for_external_images.empty())
526  {
527  const string filName =
529  format(
530  "_CONF_%f.%s",
531  (double)timestampTotime_t(obs.timestamp),
532  m_external_images_format.c_str());
534  m_path_for_external_images + string("/") + filName,
536  obs.confidenceImage.setExternalStorage(filName);
537  }
538  }
539  }
540  break;
541 
542  default:
543  break;
544  }
545  }
546 
547  // Save the observation to the user's object:
548  _out_obs.swap(obs);
549 
550  there_is_obs = true;
551 
552  // preview in real-time?
553  if (m_preview_window)
554  {
555  if (_out_obs.hasRangeImage)
556  {
557  static int decim = 0;
558  if (++decim > 10)
559  {
560  decim = 0;
561  if (!m_win_range)
562  {
563  m_win_range =
564  mrpt::make_aligned_shared<mrpt::gui::CDisplayWindow>(
565  "Preview RANGE");
566  m_win_range->setPos(5, 5);
567  }
568 
570  // Normalize the image
571  math::CMatrixFloat range2D = _out_obs.rangeImage;
572  range2D *= 1.0 / m_maxRange;
573  img.setFromMatrix(range2D);
574  m_win_range->showImage(img);
575  }
576  }
577  if (_out_obs.hasIntensityImage)
578  {
579  static int decim = 0;
580  if (++decim > 10)
581  {
582  decim = 0;
583  if (!m_win_int)
584  {
585  m_win_int =
586  mrpt::make_aligned_shared<mrpt::gui::CDisplayWindow>(
587  "Preview INTENSITY");
588  m_win_int->setPos(300, 5);
589  }
590  m_win_int->showImage(_out_obs.intensityImage);
591  }
592  }
593  }
594  else
595  {
596  if (m_win_range) m_win_range.clear();
597  if (m_win_int) m_win_int.clear();
598  }
599 
600  return;
601 #else
602  MRPT_UNUSED_PARAM(_out_obs);
603  MRPT_UNUSED_PARAM(there_is_obs);
604  MRPT_UNUSED_PARAM(hardware_error);
605 #endif
606 }
607 
608 /* -----------------------------------------------------
609  setPathForExternalImages
610 ----------------------------------------------------- */
612  const std::string& directory)
613 {
614  return;
615  // Ignore for now. It seems performance is better grabbing everything
616  // to a single big file than creating hundreds of smaller files per
617  // second...
618 
619  if (!mrpt::system::createDirectory(directory))
620  {
622  "Error: Cannot create the directory for externally saved images: "
623  "%s",
624  directory.c_str())
625  }
626  m_path_for_external_images = directory;
627 }
uint32_t nrows
Definition: TCamera.h:39
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
bool createDirectory(const std::string &dirName)
Creates a directory.
Definition: filesystem.cpp:158
size_t m_rows
Size of camera images, set on open()
unsigned __int16 uint16_t
Definition: rptypes.h:44
static char ALawCompressTable[128]
void appendObservation(const mrpt::serialization::CSerializable::Ptr &obj)
Like appendObservations() but for just one observation.
std::string read_string(const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
virtual void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
See the class documentation at the top for expected parameters.
void resize(unsigned int width, unsigned int height, TImageChannels nChannels, bool originTopLeft)
Changes the size of the image, erasing previous contents (does NOT scale its current content...
Definition: img/CImage.h:261
void scaleToResolution(unsigned int new_ncols, unsigned int new_nrows)
Rescale all the parameters for a new camera resolution (it raises an exception if the aspect ratio is...
Definition: TCamera.cpp:173
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
std::string m_sensorLabel
See CGenericSensor.
double DEG2RAD(const double x)
Degrees to radians.
A class for grabing "range images" from a MESA imaging SwissRanger 3D cameras (SR-2, SR-3000, SR-4k).
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.
Contains classes for various device interfaces.
bool table_16u_to_8u_init
float read_float(const std::string &section, const std::string &name, float defaultValue, bool failIfNotFound=false) const
void setExternalStorage(const std::string &fileName) noexcept
By using this method the image is marked as referenced to an external file, which will be loaded only...
Definition: CImage.cpp:1887
STL namespace.
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores (&#39;_&#39;) or any other user-given char. ...
Definition: filesystem.cpp:328
unsigned char LinearToALawSample(uint16_t sample)
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig()
bool m_save_3d
Save the 3D point cloud (default: true)
void loadFromConfigFile(const std::string &section, const mrpt::config::CConfigFileBase &cfg)
Load all the params from a config source, in the format used in saveToConfigFile(), that is:
Definition: TCamera.cpp:135
bool m_save_confidence
Save the estimated confidence 2D image (default: false)
int read_int(const std::string &section, const std::string &name, int defaultValue, bool failIfNotFound=false) const
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
unsigned char uint8_t
Definition: rptypes.h:41
mrpt::math::CMatrixDouble33 intrinsicParams
Matrix of intrinsic parameters (containing the focal length and principal point coordinates) ...
Definition: TCamera.h:42
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:113
mrpt::gui::CDisplayWindow::Ptr m_win_range
This class allows loading and storing values and vectors of different types from a configuration text...
bool getMesaLibVersion(std::string &out_version) const
Get the version of the MESA library.
GLint GLvoid * img
Definition: glext.h:3763
void swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
bool m_save_intensity_img
Save the 2D intensity image (default: true)
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
This namespace contains representation of robot actions and observations.
uint64_t read_uint64_t(const std::string &section, const std::string &name, uint64_t defaultValue, bool failIfNotFound=false) const
bool m_open_from_usb
true: USB, false: ETH
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
bool hasRangeImage
true means the field rangeImage contains valid data
static std::string & trim(std::string &s)
double m_maxRange
Max range, as deducted from the camera frequency.
bool m_save_range_img
Save the 2D range image (default: true)
mrpt::img::CImage confidenceImage
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the ca...
bool hasPoints3D
true means the field points3D contains valid data.
GLsizei const GLchar ** string
Definition: glext.h:4101
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
bool m_preview_window
Show preview window while grabbing.
std::array< double, 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
Definition: TCamera.h:45
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
Definition: CObservation.h:62
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:60
uint8_t table_16u_to_8u[0x10000]
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
bool isOpen() const
whether the camera is open and comms work ok.
bool read_bool(const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
unsigned int m_external_images_jpeg_quality
For JPEG images, the quality (default=95%).
GLenum GLenum GLvoid * row
Definition: glext.h:3576
void do_init_table_16u_to_8u()
bool hasIntensityImage
true means the field intensityImage contains valid data
unsigned int m_cam_serial_num
Serial number of the camera, set on open()
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
Definition: CPose3D.cpp:239
virtual void setPathForExternalImages(const std::string &directory)
Set the path where to save off-rawlog image files (this class DOES take into account this path)...
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().
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
GLenum GLint GLint y
Definition: glext.h:3538
std::string m_external_images_format
The extension ("jpg","gif","png",...) that determines the format of images saved externally.
std::string trim(const std::string &str)
Removes leading and trailing spaces.
bool saveToFile(const std::string &fileName, int jpeg_quality=95) const
Save the image to a file, whose format is determined from the extension (internally uses OpenCV)...
Definition: CImage.cpp:296
GLenum GLint x
Definition: glext.h:3538
std::string m_path_for_external_images
The path where to save off-rawlog images: empty means save images embedded in the rawlog...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
Definition: exceptions.h:43
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
void equalizeHistInPlace()
Equalize the image histogram, replacing the original image.
Definition: CImage.cpp:2517
void * m_cam
opaque handler to SRCAM.
uint32_t ncols
Camera resolution.
Definition: TCamera.h:39
double timestampTotime_t(const mrpt::system::TTimeStamp t)
Transform from TTimeStamp to standard "time_t" (actually a double number, it can contain fractions of...
Definition: datetime.cpp:50
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
unsigned char * get_unsafe(unsigned int col, unsigned int row, unsigned int channel=0) const
Access to pixels without checking boundaries - Use normally the () operator better, which checks the coordinates.
Definition: CImage.cpp:491
float maxRange
The maximum range allowed by the device, in meters (e.g.
bool hasConfidenceImage
true means the field confidenceImage contains valid data
mrpt::gui::CDisplayWindow::Ptr m_win_int
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186
bool open()
return false on error - Called automatically from initialize(), no need normally for the user to call...



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