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