MRPT  2.0.3
CCameraSensor.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
14 #include <mrpt/obs/CObservation.h>
15 #include <mrpt/poses/CPose3D.h>
17 
23 #include <mrpt/hwdrivers/CKinect.h>
28 
31 
33 #include <functional>
34 #include <memory> // unique_ptr
35 
36 namespace mrpt::hwdrivers
37 {
38 /** The central class for camera grabbers in MRPT, implementing the "generic
39  * sensor" interface.
40  * This class provides the user with a uniform interface to a variety of
41  * other classes which manage only one specific camera "driver" (opencv, ffmpeg,
42  * PGR FlyCapture,...)
43  *
44  * Following the "generic sensor" interface, all the parameters must be
45  * passed int the form of a configuration file,
46  * which may be also formed on the fly (without being a real config file) as
47  * in this example:
48  *
49  * \code
50  * CCameraSensor myCam;
51  * const string str =
52  * "[CONFIG]\n"
53  * "grabber_type=opencv\n";
54  *
55  * CConfigFileMemory cfg(str);
56  * myCam.loadConfig(cfg,"CONFIG");
57  * myCam.initialize();
58  * CObservation::Ptr obs = myCam.getNextFrame();
59  * \endcode
60  *
61  * Images can be retrieved through the normal "doProcess()" interface, or the
62  * specific method "getNextFrame()".
63  *
64  * Some notes:
65  * - "grabber_type" determines the class to use internally for image capturing
66  * (see below).
67  * - For the meaning of cv_camera_type and other parameters, refer to
68  * mrpt::hwdrivers::CImageGrabber_OpenCV
69  * - For the parameters of dc1394 parameters, refer to generic IEEE1394
70  * documentation, and to mrpt::hwdrivers::TCaptureOptions_dc1394.
71  * - If the high number of existing parameters annoy you, try the function
72  * prepareVideoSourceFromUserSelection(),
73  * which displays a GUI dialog to the user so he/she can choose the desired
74  * camera & its parameters.
75  *
76  * Images can be saved in the "external storage" mode. Detached threads are
77  * created for this task. See \a setPathForExternalImages() and \a
78  * setExternalImageFormat().
79  * These methods are called automatically from the app rawlog-grabber.
80  *
81  * These is the list of all accepted parameters:
82  *
83  * \code
84  * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
85  * -------------------------------------------------------
86  * [supplied_section_name]
87  * # Select one of the grabber implementations -----------------------
88  * grabber_type = opencv | dc1394 | bumblebee_dc1394 | ffmpeg | rawlog
89  * | swissranger | svs | kinect | flycap | flycap_stereo | image_dir | duo3d |
90  * myntd
91  *
92  * # Options for any grabber_type ------------------------------------
93  * preview_decimation = 0 // N<=0 (or not present): No preview; N>0,
94  * display 1 out of N captured frames.
95  * preview_reduction = 0 // 0 or 1 (or not present): The preview shows
96  * the actual image. For 2,3,..., reduces the size of the image by that factor,
97  * only for the preview window.
98  * capture_grayscale = 0 // 1:capture in grayscale, whenever the driver
99  * allows it. Default=0
100  * # For externaly stored images, the format of image files (default=jpg)
101  * #external_images_format = jpg
102  *
103  * # For externaly stored images: whether to spawn independent threads to
104  * save the image files.
105  * #external_images_own_thread = 1 // 0 or 1
106  *
107  * # If external_images_own_thread=1, this changes the number of threads to
108  * launch
109  * # to save image files. The default is determined from
110  * mrpt::system::getNumberOfProcessors()
111  * # and should be OK unless you want to save processor time for other
112  * things.
113  * #external_images_own_thread_count = 2 // >=1
114  *
115  * # (Only when external_images_format=jpg): Optional parameter to set the
116  * JPEG compression quality:
117  * #external_images_jpeg_quality = 95 // [1-100]. Default: 95
118  *
119  * # Pose of the sensor on the robot:
120  * pose_x=0 ; (meters)
121  * pose_y=0
122  * pose_z=0
123  * pose_yaw=0 ; (Angles in degrees)
124  * pose_pitch=0
125  * pose_roll=0
126  *
127  * # Options for grabber_type= opencv ------------------------------------
128  * cv_camera_index = 0 // [opencv] Number of camera to open
129  * cv_camera_type = CAMERA_CV_AUTODETECT
130  * cv_frame_width = 640 // [opencv] Capture width (not present or set
131  * to 0 for default)
132  * cv_frame_height = 480 // [opencv] Capture height (not present or set
133  * to 0 for default)
134  * cv_fps = 15 // [opencv] IEEE1394 cams only: Capture FPS
135  * (not present or 0 for default)
136  * cv_gain = 0 // [opencv] Camera gain, if available (nor
137  * present or set to 0 for default).
138  *
139  * # Options for grabber_type= dc1394 -------------------------------------
140  * dc1394_camera_guid = 0 | 0x11223344 // 0 (or not present): the first
141  * camera; A hexadecimal number: The GUID of the camera to open
142  * dc1394_camera_unit = 0 // 0 (or not present): the first
143  * camera; 0,1,2,...: The unit number (within the given GUID) of the camera to
144  * open (Stereo cameras: 0 or 1)
145  * dc1394_frame_width = 640
146  * dc1394_frame_height = 480
147  * dc1394_framerate = 15 // eg: 7.5, 15, 30, 60,
148  * etc... For possibilities see mrpt::hwdrivers::TCaptureOptions_dc1394
149  * dc1394_mode7 = -1 // -1: Ignore, i>=0, set to
150  * MODE7_i
151  * dc1394_color_coding = COLOR_CODING_YUV422 // For possibilities see
152  * mrpt::hwdrivers::TCaptureOptions_dc1394
153  * # Options for setting feature values: dc1394_<feature> = <n>
154  * # with <feature> = brightness | exposure | sharpness | white_balance |
155  * gamma | shutter | gain
156  * # <n> a value, or -1 (or not present) for not to change this feature
157  * value in the camera, possible values are shown in execution
158  * dc1394_shutter = -1
159  * # Options for setting feature modes: dc1394_<feature>_mode = <n>
160  * # with <feature> = brightness | exposure | sharpness | white_balance |
161  * gamma | shutter | gain
162  * # <n> = -1 (or not present) [not to change] | 0 [manual] | 1 [auto]
163  * | 2 [one_push_auto]
164  * dc1394_shutter_mode = -1
165  * # Options for setting trigger options:
166  * dc1394_trigger_power = -1 // -1 (or not present) for not to change
167  * | 0 [OFF] | 1 [ON]
168  * dc1394_trigger_mode = -1 // -1 (or not present) for not to change |
169  * 0..7 corresponding to possible modes 0,1,2,3,4,5,14,15
170  * dc1394_trigger_source= -1 // -1 (or not present) for not to change |
171  * 0..4 corresponding to possible sources 0,1,2,3,SOFTWARE
172  * dc1394_trigger_polarity = -1 // -1 (or not present) for not to change | 0
173  * [ACTIVE_LOW] | 1 [ACTIVE_HIGH]
174  * dc1394_ring_buffer_size = 15 // Length of frames ring buffer (internal
175  * to libdc1394)
176  *
177  * # Options for grabber_type= bumblebee_dc1394
178  * ----------------------------------
179  * bumblebee_dc1394_camera_guid = 0 | 0x11223344 // 0 (or not present):
180  * the first camera; A hexadecimal number: The GUID of the camera to open
181  * bumblebee_dc1394_camera_unit = 0 // 0 (or not present):
182  * the first camera; 0,1,2,...: The unit number (within the given GUID) of the
183  * camera to open (Stereo cameras: 0 or 1)
184  * bumblebee_dc1394_framerate = 15 // eg: 7.5, 15, 30,
185  * 60, etc... For possibilities see mrpt::hwdrivers::TCaptureOptions_dc1394
186  *
187  * # Options for grabber_type= ffmpeg -------------------------------------
188  * ffmpeg_url = rtsp://127.0.0.1 // [ffmpeg] The video file
189  * or IP camera to open
190  *
191  * # Options for grabber_type= rawlog -------------------------------------
192  * rawlog_file = mylog.rawlog // [rawlog] This can be
193  * used to simulate the capture of images already grabbed in the past in the
194  * form of a MRPT rawlog.
195  * rawlog_camera_sensor_label = CAMERA1 // [rawlog] If this field
196  * is not present, all images found in the rawlog will be retrieved. Otherwise,
197  * only those observations with a matching sensor label.
198  *
199  * # Options for grabber_type= svs -------------------------------------
200  * svs_camera_index = 0
201  * svs_frame_width = 800
202  * svs_frame_height = 600
203  * svs_framerate = 25.0
204  * svs_NDisp = ...
205  * svs_Corrsize = ...
206  * svs_LR = ...
207  * svs_Thresh = ...
208  * svs_Unique = ...
209  * svs_Horopter = ...
210  * svs_SpeckleSize = ...
211  * svs_procesOnChip = false
212  * svs_calDisparity = true
213  *
214  * # Options for grabber_type= swissranger
215  * -------------------------------------
216  * sr_use_usb = true // True: use USB, false: use
217  * ethernet
218  * sr_IP = 192.168.2.14 // If sr_use_usb=false, the camera
219  * IP
220  * sr_grab_grayscale = true // whether to save the intensity
221  * channel
222  * sr_grab_3d = true // whether to save the 3D points
223  * sr_grab_range = true // whether to save the range image
224  * sr_grab_confidence = true // whether to save the confidence
225  * image
226  *
227  * # Options for grabber_type= XBox kinect
228  * -------------------------------------
229  * kinect_grab_intensity = true // whether to save the intensity
230  * (RGB) channel
231  * kinect_grab_3d = true // whether to save the 3D points
232  * kinect_grab_range = true // whether to save the depth
233  * image
234  * #kinect_video_rgb = true // Optional. If set to "false",
235  * the IR intensity channel will be grabbed instead of the color RGB channel.
236  *
237  * # Options for grabber_type= flycap (Point Grey Research's FlyCapture 2
238  * for Monocular and Stereo cameras, e.g. Bumblebee2) --------
239  * flycap_camera_index = 0
240  * #... (all the parameters enumerated in
241  * mrpt::hwdrivers::TCaptureOptions_FlyCapture2 with the prefix "flycap_")
242  *
243  * # Options for grabber_type= flycap_stereo (Point Grey Research's
244  * FlyCapture 2, two cameras setup as a stereo pair) ------
245  * # fcs_start_synch_capture = false // *Important*: Only set to true if
246  * using Firewire cameras: the "startSyncCapture()" command is unsupported in
247  * USB3 and GigaE cameras.
248  *
249  * fcs_LEFT_camera_index = 0
250  * #... (all the parameters enumerated in
251  * mrpt::hwdrivers::TCaptureOptions_FlyCapture2 with the prefix "fcs_LEFT_")
252  * fcs_RIGHT_camera_index = 0
253  * #... (all the parameters enumerated in
254  * mrpt::hwdrivers::TCaptureOptions_FlyCapture2 with the prefix "fcs_RIGHT_")
255  *
256  * # Options for grabber_type= image_dir
257  * image_dir_url = // [string] URL of the
258  * directory
259  * left_filename_format = imL_%05d.jpg // [string] Format
260  * including prefix, number of trailing zeros, digits and image format
261  * (extension)
262  * right_filename_format = imR_%05d.jpg // [string] Format
263  * including prefix, number of trailing zeros, digits and image format
264  * (extension). Leave blank if only images from one camera will be used.
265  * start_index = 0 // [int]
266  * Starting index for images
267  * end_index = 100 // [int] End index
268  * for the images
269  *
270  * # Options for grabber_type= myntd ------------------------------------
271  * myntd_xxx =
272  *
273  * # Options for grabber_type= duo3d
274  * Create a section like this:
275  * [DUO3DOptions]
276  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore
277  * this section (it is not a separate device!)
278  *
279  * image_width = 640 // [int] x Resolution
280  * image_height = 480 // [int] y Resolution
281  * fps = 30 // [int] Frames per second
282  * (<= 30)
283  * exposure = 50 // [int] Exposure value (1..100)
284  * led = 0 // [int] Led intensity
285  * (only for some device models) (1..100).
286  * gain = 50 // [int] Camera gain (1..100)
287  * capture_rectified = false // [bool] Rectify
288  * captured images
289  * capture_imu = true // [bool] Capture IMU data
290  * from DUO3D device (if available)
291  * calibration_from_file = true // [bool] Use YML
292  * calibration files provided by calibration application supplied with DUO3D
293  * device
294  * intrinsic_filename = "" // [string] Intrinsic
295  * parameters file. This filename should contain a substring _RWWWxHHH_ with WWW
296  * being the image width and HHH the image height, as provided by the
297  * calibration application.
298  * extrinsic_filename = "" // [string] Extrinsic
299  * parameters file. This filename should contain a substring _RWWWxHHH_ with WWW
300  * being the image width and HHH the image height, as provided by the
301  * calibration application.
302  * rectify_map_filename = "" // [string] Rectification map
303  * file. This filename should contain a substring _RWWWxHHH_ with WWW being the
304  * image width and HHH the image height, as provided by the calibration
305  * application.
306  *
307  * // if 'calibration_from_file' = false, three more sections containing the
308  * calibration must be provided:
309  * [DUO3D_LEFT]
310  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore
311  * this section (it is not a separate device!)
312  * resolution = [640 480]
313  * cx = 320
314  * cy = 240
315  * fx = 700
316  * fy = 700
317  * dist = [0 0 0 0 0]
318  *
319  * [DUO3D_RIGHT]
320  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore
321  * this section (it is not a separate device!)
322  * resolution = [640 480]
323  * cx = 320
324  * cy = 240
325  * fx = 700
326  * fy = 700
327  * dist = [0 0 0 0 0]
328  *
329  * [DUO3D_LEFT2RIGHT_POSE]
330  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore
331  * this section (it is not a separate device!)
332  * pose_quaternion = [0.12 0 0 1 0 0 0]
333  *
334  * \endcode
335  *
336  * \note The execution rate, in rawlog-grabber or the user code calling
337  * doProcess(), should be greater than the required capture FPS.
338  * \note In Linux you may need to execute "chmod 666 /dev/video1394/ * " and
339  * "chmod 666 /dev/raw1394" for allowing any user R/W access to firewire
340  * cameras.
341  * \note [New in MRPT 1.4.0] The `bumblebee` driver has been deleted, use the
342  * `flycap` driver in stereo mode.
343  * \sa mrpt::hwdrivers::CImageGrabber_OpenCV,
344  * mrpt::hwdrivers::CImageGrabber_dc1394, CGenericSensor,
345  * prepareVideoSourceFromUserSelection()
346  * \ingroup mrpt_hwdrivers_grp
347  */
349 {
351 
352  public:
353  using Ptr = std::shared_ptr<CCameraSensor>;
354  /** Constructor. The camera is not open until "initialize" is called. */
355  CCameraSensor();
356 
357  /** Destructor */
358  ~CCameraSensor() override;
359 
360  // See docs in parent class
361  void doProcess() override;
362 
363  /** Retrieves the next frame from the video source, raising an exception on
364  *any error.
365  * Note: The returned observations can be of one of these classes (you can
366  *use IS_CLASS(obs,CObservationXXX) to determine it):
367  * - mrpt::obs::CObservationImage (For normal cameras or video sources)
368  * - mrpt::obs::CObservationStereoImages (For stereo cameras)
369  * - mrpt::obs::CObservation3DRangeScan (For 3D cameras)
370  */
372  void getNextFrame(
373  std::vector<mrpt::serialization::CSerializable::Ptr>& out_obs);
374 
375  /** Tries to open the camera, after setting all the parameters with a call
376  * to loadConfig.
377  * \exception This method must throw an exception with a descriptive
378  * message if some critical error is found.
379  */
380  void initialize() override;
381 
382  /** Close the camera (if open).
383  * This method is called automatically on destruction.
384  */
385  void close();
386 
387  /** Set Software trigger level value (ON or OFF) for cameras with this
388  * function available.
389  */
390  void setSoftwareTriggerLevel(bool level);
391 
392  /** Set the path where to save off-rawlog image files (this class DOES take
393  * into account this path).
394  * An empty string (the default value at construction) means to save
395  * images embedded in the rawlog, instead of on separate files.
396  * \exception std::exception If the directory doesn't exists and cannot be
397  * created.
398  */
399  void setPathForExternalImages(const std::string& directory) override;
400 
401  /** This must be called before initialize() */
402  void enableLaunchOwnThreadForSavingImages(bool enable = true)
403  {
405  };
406 
407  /** Functor type */
408  using TPreSaveUserHook = std::function<void(
409  const mrpt::obs::CObservation::Ptr& obs, void* user_ptr)>;
410 
411  /** Provides a "hook" for user-code to be run BEFORE an image is going to be
412  * saved to disk if external storage is enabled (e.g. to rectify images,
413  * preprocess them, etc.)
414  * Notice that this code may be called from detached threads, so it must be
415  * thread safe.
416  * If used, call this before initialize() */
417  void addPreSaveHook(TPreSaveUserHook user_function, void* user_ptr)
418  {
419  m_hook_pre_save = user_function;
420  m_hook_pre_save_param = user_ptr;
421  };
422 
423  protected:
424  // Options for any grabber_type ------------------------------------
426 
427  /** Can be "opencv",... */
428  std::string m_grabber_type;
429  bool m_capture_grayscale{false};
430 
431  // Options for grabber_type= opencv ------------------------------------
433  std::string m_cv_camera_type;
435 
436  // Options for grabber_type= dc1394 -------------------------------------
437  uint64_t m_dc1394_camera_guid{0};
442 
443  // Options for grabber_type= bumblebee_dc1394
444  // ----------------------------------
448 
449  // Options for grabber type= svs -----------------------------------------
452 
453  // Options for grabber_type= ffmpeg -------------------------------------
454  std::string m_ffmpeg_url;
455 
456  // Options for grabber_type= rawlog -------------------------------------
457  std::string m_rawlog_file;
460 
461  // Options for grabber_type= swissranger
462  // -------------------------------------
463  /** true: USB, false: ETH */
464  bool m_sr_open_from_usb{true};
465  std::string m_sr_ip_address;
466  /** Save the 3D point cloud (default: true) */
467  bool m_sr_save_3d{true};
468  /** Save the 2D range image (default: true) */
470  /** Save the 2D intensity image (default: true) */
472  /** Save the estimated confidence 2D image (default: false) */
474 
475  // Options for grabber_type= XBox kinect
476  // -------------------------------------
477  /** Save the 3D point cloud (default: true) */
478  bool m_kinect_save_3d{true};
479  /** Save the 2D range image (default: true) */
481  /** Save the 2D intensity image (default: true) */
483  /** Save RGB or IR channels (default:true) */
484  bool m_kinect_video_rgb{true};
485 
486  // Options for grabber type= flycap
487  // -----------------------------------------
489 
490  // Options for grabber type= myntd
491  // -----------------------------------------
493 
494  // Options for grabber type= flycap_stereo
495  // -----------------------------------------
498  m_flycap_stereo_options[2]; // [0]:left, [1]:right
499 
500  // Options for grabber type= image_dir
501  std::string m_img_dir_url;
506 
509 
510  // Options for grabber type= duo3d
512 
513  // Other options:
514  /** Whether to launch independent thread */
516 
517  /** See the class documentation at the top for expected parameters */
519  const mrpt::config::CConfigFileBase& configSource,
520  const std::string& iniSection) override;
521 
522  private:
523  // Only one of these will be !=nullptr at a time ===========
524  /** The OpenCV capture object. */
525  std::unique_ptr<CImageGrabber_OpenCV> m_cap_cv;
526  /** The dc1394 capture object. */
527  std::unique_ptr<CImageGrabber_dc1394> m_cap_dc1394;
528  /** The FlyCapture2 object */
529  std::unique_ptr<CImageGrabber_FlyCapture2> m_cap_flycap;
530  /** The FlyCapture2 object for stereo pairs */
531  std::unique_ptr<CImageGrabber_FlyCapture2> m_cap_flycap_stereo_l,
533  std::unique_ptr<CStereoGrabber_Bumblebee_libdc1394> m_cap_bumblebee_dc1394;
534  /** The svs capture object. */
535  std::unique_ptr<CStereoGrabber_SVS> m_cap_svs;
536  /** The FFMPEG capture object */
537  std::unique_ptr<CFFMPEG_InputStream> m_cap_ffmpeg;
538  /** The input file for rawlogs */
539  std::unique_ptr<mrpt::io::CFileGZInputStream> m_cap_rawlog;
540  /** SR 3D camera object. */
541  std::unique_ptr<CSwissRanger3DCamera> m_cap_swissranger;
542  /** Kinect camera object. */
543  std::unique_ptr<CKinect> m_cap_kinect;
544  /** OpenNI2 object. */
545  std::unique_ptr<COpenNI2Sensor> m_cap_openni2;
546  /** Read images from directory */
547  std::unique_ptr<std::string> m_cap_image_dir;
548  /** The DUO3D capture object */
549  std::unique_ptr<CDUO3DCamera> m_cap_duo3d;
550  /** The MYNT EYE capture object */
551  std::unique_ptr<CMyntEyeCamera> m_myntd;
552  // =========================
553 
556 
558  /** Normally we'll use only one window, but for stereo images we'll use two
559  * of them. */
561 
562  /** @name Stuff related to working threads to save images to disk
563  @{ */
564  /** Number of working threads. Default:1, set to 2 in quad cores. */
566  std::vector<std::thread> m_threadImagesSaver;
567 
569  /** The critical section for m_toSaveList */
570  std::mutex m_csToSaveList;
571  /** The queues of objects to be returned by getObservations, one for each
572  * working thread. */
573  std::vector<TListObservations> m_toSaveList;
574  /** Thread to save images to files. */
575  void thread_save_images(unsigned int my_working_thread_index);
576 
578  void* m_hook_pre_save_param{nullptr};
579  /** @} */
580 
581 }; // end class
582 
583 /** Used only from MRPT apps: Use with caution since "panel" MUST be a
584  * "mrpt::gui::CPanelCameraSelection *"
585  */
587 
588 /** Parse the user options in the wxWidgets "panel" and write the configuration
589  * into the given section of the given configuration file.
590  * Use with caution since "panel" MUST be a "mrpt::gui::CPanelCameraSelection
591  * *"
592  * \sa prepareVideoSourceFromUserSelection, prepareVideoSourceFromPanel,
593  * readConfigIntoVideoSourcePanel
594  */
596  void* panel, const std::string& in_cfgfile_section_name,
597  mrpt::config::CConfigFileBase* out_cfgfile);
598 
599 /** Parse the given section of the given configuration file and set accordingly
600  * the controls of the wxWidgets "panel".
601  * Use with caution since "panel" MUST be a "mrpt::gui::CPanelCameraSelection
602  * *"
603  * \sa prepareVideoSourceFromUserSelection, prepareVideoSourceFromPanel,
604  * writeConfigFromVideoSourcePanel
605  */
607  void* panel, const std::string& in_cfgfile_section_name,
608  const mrpt::config::CConfigFileBase* in_cfgfile);
609 
610 /** Show to the user a list of possible camera drivers and creates and open the
611  * selected camera.
612  */
614 
615 } // namespace mrpt::hwdrivers
mrpt::obs::CObservation::Ptr
std::shared_ptr< CObservation > Ptr
Definition: CObservation.h:45
mrpt::hwdrivers::CCameraSensor::setSoftwareTriggerLevel
void setSoftwareTriggerLevel(bool level)
Set Software trigger level value (ON or OFF) for cameras with this function available.
Definition: CCameraSensor.cpp:1433
mrpt::hwdrivers::CCameraSensor::m_hook_pre_save
TPreSaveUserHook m_hook_pre_save
Definition: CCameraSensor.h:577
mrpt::hwdrivers::CCameraSensor::m_cv_camera_index
int m_cv_camera_index
Definition: CCameraSensor.h:432
mrpt::hwdrivers::CCameraSensor::m_rawlog_file
std::string m_rawlog_file
Definition: CCameraSensor.h:457
mrpt::hwdrivers::CCameraSensor::m_preview_win1
mrpt::gui::CDisplayWindow::Ptr m_preview_win1
Normally we'll use only one window, but for stereo images we'll use two of them.
Definition: CCameraSensor.h:560
mrpt::hwdrivers::CCameraSensor::m_img_dir_is_stereo
bool m_img_dir_is_stereo
Definition: CCameraSensor.h:507
CStereoGrabber_SVS.h
mrpt::hwdrivers::CCameraSensor::m_kinect_video_rgb
bool m_kinect_video_rgb
Save RGB or IR channels (default:true)
Definition: CCameraSensor.h:484
mrpt::hwdrivers::CCameraSensor::m_cap_image_dir
std::unique_ptr< std::string > m_cap_image_dir
Read images from directory.
Definition: CCameraSensor.h:547
mrpt::hwdrivers::CCameraSensor::m_kinect_save_intensity_img
bool m_kinect_save_intensity_img
Save the 2D intensity image (default: true)
Definition: CCameraSensor.h:482
CImageGrabber_FlyCapture2.h
mrpt::hwdrivers::CCameraSensor::m_cap_flycap_stereo_l
std::unique_ptr< CImageGrabber_FlyCapture2 > m_cap_flycap_stereo_l
The FlyCapture2 object for stereo pairs.
Definition: CCameraSensor.h:531
mrpt::hwdrivers::CCameraSensor::CCameraSensor
CCameraSensor()
Constructor.
Definition: CCameraSensor.cpp:46
mrpt::hwdrivers::CCameraSensor::initialize
void initialize() override
Tries to open the camera, after setting all the parameters with a call to loadConfig.
Definition: CCameraSensor.cpp:75
mrpt::hwdrivers::CCameraSensor
The central class for camera grabbers in MRPT, implementing the "generic sensor" interface.
Definition: CCameraSensor.h:348
mrpt::hwdrivers::CCameraSensor::m_bumblebee_dc1394_camera_unit
int m_bumblebee_dc1394_camera_unit
Definition: CCameraSensor.h:446
CDUO3DCamera.h
mrpt::hwdrivers::CCameraSensor::m_myntd
std::unique_ptr< CMyntEyeCamera > m_myntd
The MYNT EYE capture object.
Definition: CCameraSensor.h:551
mrpt::hwdrivers::CCameraSensor::m_cap_flycap_stereo_r
std::unique_ptr< CImageGrabber_FlyCapture2 > m_cap_flycap_stereo_r
Definition: CCameraSensor.h:532
mrpt::hwdrivers::CCameraSensor::m_bumblebee_dc1394_camera_guid
uint64_t m_bumblebee_dc1394_camera_guid
Definition: CCameraSensor.h:445
mrpt::hwdrivers::TCaptureOptions_FlyCapture2
Options used when creating a camera capture object of type CImageGrabber_FlyCapture2.
Definition: CImageGrabber_FlyCapture2.h:18
mrpt::hwdrivers::TCaptureOptions_SVS
Options used when creating a STOC Videre Design camera capture object.
Definition: CStereoGrabber_SVS.h:18
mrpt::hwdrivers::CCameraSensor::m_duo3d_options
TCaptureOptions_DUO3D m_duo3d_options
Definition: CCameraSensor.h:511
mrpt::hwdrivers::CCameraSensor::m_camera_grab_decimator_counter
int m_camera_grab_decimator_counter
Definition: CCameraSensor.h:555
COpenNI2Sensor.h
mrpt::hwdrivers
Contains classes for various device interfaces.
Definition: C2DRangeFinderAbstract.h:19
mrpt::hwdrivers::CCameraSensor::m_kinect_save_range_img
bool m_kinect_save_range_img
Save the 2D range image (default: true)
Definition: CCameraSensor.h:480
mrpt::hwdrivers::CCameraSensor::m_rawlog_camera_sensor_label
std::string m_rawlog_camera_sensor_label
Definition: CCameraSensor.h:458
mrpt::hwdrivers::CCameraSensor::m_img_dir_counter
int m_img_dir_counter
Definition: CCameraSensor.h:508
mrpt::hwdrivers::CCameraSensor::m_preview_decimation
int m_preview_decimation
Definition: CCameraSensor.h:440
DEFINE_GENERIC_SENSOR
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
Definition: CGenericSensor.h:302
mrpt::hwdrivers::TCaptureOptions_DUO3D
Options used when creating a camera capture object of type CImageGrabber_FlyCapture2.
Definition: CDUO3DCamera.h:20
mrpt::hwdrivers::CCameraSensor::m_grabber_type
std::string m_grabber_type
Can be "opencv",...
Definition: CCameraSensor.h:428
CImageGrabber_OpenCV.h
mrpt::hwdrivers::CCameraSensor::m_bumblebee_dc1394_framerate
double m_bumblebee_dc1394_framerate
Definition: CCameraSensor.h:447
CStereoGrabber_Bumblebee_libdc1394.h
mrpt::hwdrivers::CCameraSensor::m_sr_ip_address
std::string m_sr_ip_address
Definition: CCameraSensor.h:465
mrpt::hwdrivers::CCameraSensor::setPathForExternalImages
void setPathForExternalImages(const std::string &directory) override
Set the path where to save off-rawlog image files (this class DOES take into account this path).
Definition: CCameraSensor.cpp:1453
mrpt::gui::CDisplayWindow::Ptr
std::shared_ptr< CDisplayWindow > Ptr
Definition: CDisplayWindow.h:36
mrpt::hwdrivers::CCameraSensor::enableLaunchOwnThreadForSavingImages
void enableLaunchOwnThreadForSavingImages(bool enable=true)
This must be called before initialize()
Definition: CCameraSensor.h:402
CConfigFileBase.h
mrpt::hwdrivers::CCameraSensor::m_cap_ffmpeg
std::unique_ptr< CFFMPEG_InputStream > m_cap_ffmpeg
The FFMPEG capture object.
Definition: CCameraSensor.h:537
mrpt::hwdrivers::prepareVideoSourceFromUserSelection
CCameraSensor::Ptr prepareVideoSourceFromUserSelection()
Show to the user a list of possible camera drivers and creates and open the selected camera.
Definition: CCameraSensor.cpp:1467
mrpt::hwdrivers::CCameraSensor::m_svs_options
TCaptureOptions_SVS m_svs_options
Definition: CCameraSensor.h:451
mrpt::hwdrivers::CCameraSensor::m_cap_cv
std::unique_ptr< CImageGrabber_OpenCV > m_cap_cv
The OpenCV capture object.
Definition: CCameraSensor.h:525
mrpt::hwdrivers::CCameraSensor::m_sr_save_confidence
bool m_sr_save_confidence
Save the estimated confidence 2D image (default: false)
Definition: CCameraSensor.h:473
mrpt::hwdrivers::CCameraSensor::m_cap_duo3d
std::unique_ptr< CDUO3DCamera > m_cap_duo3d
The DUO3D capture object.
Definition: CCameraSensor.h:549
mrpt::hwdrivers::CCameraSensor::getNextFrame
mrpt::obs::CObservation::Ptr getNextFrame()
Retrieves the next frame from the video source, raising an exception on any error.
Definition: CCameraSensor.cpp:727
mrpt::hwdrivers::CCameraSensor::m_img_dir_left_format
std::string m_img_dir_left_format
Definition: CCameraSensor.h:502
mrpt::hwdrivers::CCameraSensor::addPreSaveHook
void addPreSaveHook(TPreSaveUserHook user_function, void *user_ptr)
Provides a "hook" for user-code to be run BEFORE an image is going to be saved to disk if external st...
Definition: CCameraSensor.h:417
COutputLogger.h
CImageGrabber_dc1394.h
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::hwdrivers::CCameraSensor::m_cap_dc1394
std::unique_ptr< CImageGrabber_dc1394 > m_cap_dc1394
The dc1394 capture object.
Definition: CCameraSensor.h:527
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
CGenericSensor.h
mrpt::hwdrivers::CCameraSensor::m_cap_bumblebee_dc1394
std::unique_ptr< CStereoGrabber_Bumblebee_libdc1394 > m_cap_bumblebee_dc1394
Definition: CCameraSensor.h:533
mrpt::hwdrivers::CCameraSensor::m_toSaveList
std::vector< TListObservations > m_toSaveList
The queues of objects to be returned by getObservations, one for each working thread.
Definition: CCameraSensor.h:573
mrpt::hwdrivers::CCameraSensor::m_dc1394_camera_unit
int m_dc1394_camera_unit
Definition: CCameraSensor.h:438
mrpt::hwdrivers::CCameraSensor::m_cap_swissranger
std::unique_ptr< CSwissRanger3DCamera > m_cap_swissranger
SR 3D camera object.
Definition: CCameraSensor.h:541
mrpt::hwdrivers::CCameraSensor::m_ffmpeg_url
std::string m_ffmpeg_url
Definition: CCameraSensor.h:454
mrpt::hwdrivers::CCameraSensor::m_img_dir_start_index
int m_img_dir_start_index
Definition: CCameraSensor.h:504
mrpt::hwdrivers::CCameraSensor::m_cap_flycap
std::unique_ptr< CImageGrabber_FlyCapture2 > m_cap_flycap
The FlyCapture2 object.
Definition: CCameraSensor.h:529
mrpt::hwdrivers::CCameraSensor::m_preview_counter
int m_preview_counter
Definition: CCameraSensor.h:557
mrpt::hwdrivers::CCameraSensor::m_cap_rawlog
std::unique_ptr< mrpt::io::CFileGZInputStream > m_cap_rawlog
The input file for rawlogs.
Definition: CCameraSensor.h:539
mrpt::hwdrivers::CCameraSensor::m_external_image_saver_count
unsigned int m_external_image_saver_count
Number of working threads.
Definition: CCameraSensor.h:565
mrpt::hwdrivers::CCameraSensor::TPreSaveUserHook
std::function< void(const mrpt::obs::CObservation::Ptr &obs, void *user_ptr)> TPreSaveUserHook
Functor type.
Definition: CCameraSensor.h:409
mrpt::hwdrivers::CCameraSensor::m_myntd_options
TMyntEyeCameraParameters m_myntd_options
Definition: CCameraSensor.h:492
mrpt::hwdrivers::CCameraSensor::m_img_dir_end_index
int m_img_dir_end_index
Definition: CCameraSensor.h:505
mrpt::hwdrivers::prepareVideoSourceFromPanel
CCameraSensor::Ptr prepareVideoSourceFromPanel(void *panel)
Used only from MRPT apps: Use with caution since "panel" MUST be a "mrpt::gui::CPanelCameraSelection ...
Definition: CCameraSensor.cpp:1542
CFFMPEG_InputStream.h
mrpt::hwdrivers::CGenericSensor
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
Definition: CGenericSensor.h:70
mrpt::hwdrivers::TCaptureOptions_dc1394
Options used when creating an dc1394 capture object All but the frame size, framerate,...
Definition: CImageGrabber_dc1394.h:47
mrpt::hwdrivers::CCameraSensor::m_capture_grayscale
bool m_capture_grayscale
Definition: CCameraSensor.h:429
mrpt::hwdrivers::CCameraSensor::m_cv_options
TCaptureCVOptions m_cv_options
Definition: CCameraSensor.h:434
mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &iniSection) override
See the class documentation at the top for expected parameters.
Definition: CCameraSensor.cpp:419
mrpt::hwdrivers::CCameraSensor::m_cap_svs
std::unique_ptr< CStereoGrabber_SVS > m_cap_svs
The svs capture object.
Definition: CCameraSensor.h:535
mrpt::system::COutputLogger
Versatile class for consistent logging and management of output messages.
Definition: system/COutputLogger.h:117
mrpt::hwdrivers::CCameraSensor::m_img_dir_right_format
std::string m_img_dir_right_format
Definition: CCameraSensor.h:503
CPose3D.h
mrpt::hwdrivers::CCameraSensor::m_external_images_own_thread
bool m_external_images_own_thread
Whether to launch independent thread.
Definition: CCameraSensor.h:515
mrpt::hwdrivers::CCameraSensor::m_csToSaveList
std::mutex m_csToSaveList
The critical section for m_toSaveList.
Definition: CCameraSensor.h:570
mrpt::hwdrivers::CCameraSensor::m_cv_camera_type
std::string m_cv_camera_type
Definition: CCameraSensor.h:433
mrpt::hwdrivers::CCameraSensor::~CCameraSensor
~CCameraSensor() override
Destructor.
Definition: CCameraSensor.cpp:717
mrpt::hwdrivers::CCameraSensor::m_flycap_options
TCaptureOptions_FlyCapture2 m_flycap_options
Definition: CCameraSensor.h:488
mrpt::hwdrivers::CCameraSensor::m_dc1394_camera_guid
uint64_t m_dc1394_camera_guid
Definition: CCameraSensor.h:437
CObservation.h
mrpt::hwdrivers::CCameraSensor::m_sr_save_range_img
bool m_sr_save_range_img
Save the 2D range image (default: true)
Definition: CCameraSensor.h:469
CKinect.h
mrpt::hwdrivers::TCaptureCVOptions
Options used when creating an OpenCV capture object Some options apply to IEEE1394 cameras only.
Definition: CImageGrabber_OpenCV.h:36
mrpt::hwdrivers::CCameraSensor::m_hook_pre_save_param
void * m_hook_pre_save_param
Definition: CCameraSensor.h:578
mrpt::hwdrivers::CCameraSensor::m_sr_save_3d
bool m_sr_save_3d
Save the 3D point cloud (default: true)
Definition: CCameraSensor.h:467
mrpt::hwdrivers::CCameraSensor::m_threadImagesSaverShouldEnd
bool m_threadImagesSaverShouldEnd
Definition: CCameraSensor.h:568
CMyntEyeCamera.h
mrpt::hwdrivers::CCameraSensor::m_svs_camera_index
int m_svs_camera_index
Definition: CCameraSensor.h:450
mrpt::hwdrivers::CCameraSensor::m_img_dir_url
std::string m_img_dir_url
Definition: CCameraSensor.h:501
CFileGZInputStream.h
mrpt::hwdrivers::CCameraSensor::m_sr_save_intensity_img
bool m_sr_save_intensity_img
Save the 2D intensity image (default: true)
Definition: CCameraSensor.h:471
mrpt::hwdrivers::TMyntEyeCameraParameters
Open parameters for CMyntEyeCamera.
Definition: CMyntEyeCamera.h:24
mrpt::hwdrivers::CCameraSensor::m_sr_open_from_usb
bool m_sr_open_from_usb
true: USB, false: ETH
Definition: CCameraSensor.h:464
mrpt::hwdrivers::CCameraSensor::close
void close()
Close the camera (if open).
Definition: CCameraSensor.cpp:390
mrpt::hwdrivers::writeConfigFromVideoSourcePanel
void writeConfigFromVideoSourcePanel(void *panel, const std::string &in_cfgfile_section_name, mrpt::config::CConfigFileBase *out_cfgfile)
Parse the user options in the wxWidgets "panel" and write the configuration into the given section of...
Definition: CCameraSensor.cpp:1574
mrpt::hwdrivers::CCameraSensor::m_kinect_save_3d
bool m_kinect_save_3d
Save the 3D point cloud (default: true)
Definition: CCameraSensor.h:478
mrpt::hwdrivers::CCameraSensor::Ptr
std::shared_ptr< CCameraSensor > Ptr
Definition: CCameraSensor.h:353
mrpt::hwdrivers::CCameraSensor::m_flycap_stereo_options
TCaptureOptions_FlyCapture2 m_flycap_stereo_options[2]
Definition: CCameraSensor.h:498
mrpt::hwdrivers::CCameraSensor::doProcess
void doProcess() override
This method will be invoked at a minimum rate of "process_rate" (Hz)
Definition: CCameraSensor.cpp:1423
mrpt::hwdrivers::CCameraSensor::m_camera_grab_decimator
int m_camera_grab_decimator
Definition: CCameraSensor.h:554
mrpt::hwdrivers::readConfigIntoVideoSourcePanel
void readConfigIntoVideoSourcePanel(void *panel, const std::string &in_cfgfile_section_name, const mrpt::config::CConfigFileBase *in_cfgfile)
Parse the given section of the given configuration file and set accordingly the controls of the wxWid...
Definition: CCameraSensor.cpp:1594
mrpt::hwdrivers::CCameraSensor::m_preview_reduction
int m_preview_reduction
Definition: CCameraSensor.h:441
mrpt::hwdrivers::CCameraSensor::m_cap_kinect
std::unique_ptr< CKinect > m_cap_kinect
Kinect camera object.
Definition: CCameraSensor.h:543
mrpt::hwdrivers::CCameraSensor::m_rawlog_detected_images_dir
std::string m_rawlog_detected_images_dir
Definition: CCameraSensor.h:459
mrpt::hwdrivers::CCameraSensor::m_threadImagesSaver
std::vector< std::thread > m_threadImagesSaver
Definition: CCameraSensor.h:566
mrpt::hwdrivers::CCameraSensor::m_sensorPose
poses::CPose3D m_sensorPose
Definition: CCameraSensor.h:421
mrpt::hwdrivers::CCameraSensor::thread_save_images
void thread_save_images(unsigned int my_working_thread_index)
Thread to save images to files.
Definition: CCameraSensor.cpp:1616
CDisplayWindow.h
mrpt::hwdrivers::CCameraSensor::m_fcs_start_synch_capture
bool m_fcs_start_synch_capture
Definition: CCameraSensor.h:496
mrpt::hwdrivers::CCameraSensor::m_preview_win2
mrpt::gui::CDisplayWindow::Ptr m_preview_win2
Definition: CCameraSensor.h:560
mrpt::hwdrivers::CCameraSensor::m_cap_openni2
std::unique_ptr< COpenNI2Sensor > m_cap_openni2
OpenNI2 object.
Definition: CCameraSensor.h:545
CSwissRanger3DCamera.h
mrpt::hwdrivers::CCameraSensor::m_dc1394_options
TCaptureOptions_dc1394 m_dc1394_options
Definition: CCameraSensor.h:439



Page generated by Doxygen 1.8.17 for MRPT 2.0.3 at Fri May 15 15:49:54 UTC 2020