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



Page generated by Doxygen 1.8.16 for MRPT 1.4.0 SVN: at Mon Oct 14 23:08:25 UTC 2019