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



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST