The central class for camera grabbers in MRPT, implementing the "generic sensor" interface.
This class provides the user with a uniform interface to a variety of other classes which manage only one specific camera "driver" (opencv, ffmpeg, bumblebee,...)
Following the "generic sensor" interface, all the parameters must be passed int the form of a configuration file, which may be also formed on the fly (without being a real config file) as in this example:
CCameraSensor myCam; const string str = "[CONFIG]\n" "grabber_type=opencv\n"; CConfigFileMemory cfg(str); myCam.loadConfig(cfg,"CONFIG"); myCam.initialize(); CObservationPtr obs = myCam.getNextFrame();
Images can be retrieved through the normal "doProcess()" interface, or the specific method "getNextFrame()".
Some notes:
Images can be saved in the "external storage" mode. See setPathForExternalImages and setExternalImageFormat. These methods are called automatically from rawlog-grabber.
These is the list of all accepted parameters:
PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS: ------------------------------------------------------- [supplied_section_name] // Select one of the grabber implementations ----------------------- grabber_type = opencv | dc1394 | bumblebee | ffmpeg | rawlog | swissranger | kinect // Options for any grabber_type ------------------------------------ preview_decimation = 0 // N<=0 (or not present): No preview; N>0, display 1 out of N captured frames. 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. capture_grayscale = 0 // 1:capture in grayscale, whenever the driver allows it. Default=0 // For externaly stored images, the format of image files (default=jpg) //external_images_format = jpg // For externaly stored images: whether to spawn independent threads to save the image files. //external_images_own_thread = 1 // 0 or 1 // If external_images_own_thread=1, this changes the number of threads to launch // to save image files. The default is determined from mrpt::system::getNumberOfProcessors() // and should be OK unless you want to save processor time for other things. //external_images_own_thread_count = 2 // >=1 // (Only when external_images_format=jpg): Optional parameter to set the JPEG compression quality: //external_images_jpeg_quality = 95 // [1-100]. Default: 95 // Pose of the sensor on the robot: pose_x=0 ; (meters) pose_y=0 pose_z=0 pose_yaw=0 ; (Angles in degrees) pose_pitch=0 pose_roll=0 // Options for grabber_type= opencv ------------------------------------ cv_camera_index = 0 // [opencv] Number of camera to open cv_camera_type = CAMERA_CV_AUTODETECT cv_frame_width = 640 // [opencv] Capture width (not present or set to 0 for default) cv_frame_height = 480 // [opencv] Capture height (not present or set to 0 for default) cv_fps = 15 // [opencv] IEEE1394 cams only: Capture FPS (not present or 0 for default) cv_gain = 0 // [opencv] Camera gain, if available (nor present or set to 0 for default). // Options for grabber_type= dc1394 ------------------------------------- dc1394_camera_guid = 0 | 0x11223344 // 0 (or not present): the first camera; A hexadecimal number: The GUID of the camera to open 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) dc1394_frame_width = 640 dc1394_frame_height = 480 dc1394_framerate = 15 // eg: 7.5, 15, 30, 60, etc... For posibilities see mrpt::hwdrivers::TCaptureOptions_dc1394 dc1394_mode7 = -1 // -1: Ignore, i>=0, set to MODE7_i dc1394_color_coding = COLOR_CODING_YUV422 // For posibilities see mrpt::hwdrivers::TCaptureOptions_dc1394 dc1394_shutter = -1 // A value, or -1 (or not present) for not to change this parameter in the camera dc1394_gain = -1 // A value, or -1 (or not present) for not to change this parameter in the camera dc1394_gamma = -1 // A value, or -1 (or not present) for not to change this parameter in the camera dc1394_brightness = -1 // A value, or -1 (or not present) for not to change this parameter in the camera dc1394_exposure = -1 // A value, or -1 (or not present) for not to change this parameter in the camera dc1394_sharpness = -1 // A value, or -1 (or not present) for not to change this parameter in the camera dc1394_white_balance = -1 // A value, or -1 (or not present) for not to change this parameter in the camera // Options for grabber_type= bumblebee ---------------------------------- bumblebee_camera_index = 0 // [bumblebee] Number of camera within the firewire bus to open (typically = 0) bumblebee_frame_width = 640 // [bumblebee] Capture width (not present or set to 0 for default) bumblebee_frame_height = 480 // [bumblebee] Capture height (not present or set to 0 for default) bumblebee_fps = 15 // [bumblebee] Capture FPS (not present or 0 for default) bumblebee_mono = 0|1 // [bumblebee] OPTIONAL: If this parameter is present, monocular (0:left, 1:right) images will be grabbed instead of stereo pairs. bumblebee_get_rectified = 0|1 // [bumblebee] Determines if the camera should grab rectified or raw images (1 is the default) // Options for grabber_type= ffmpeg ------------------------------------- ffmpeg_url = rtsp://127.0.0.1 // [ffmpeg] The video file or IP camera to open // Options for grabber_type= rawlog ------------------------------------- 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. 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. // Options for grabber_type= swissranger ------------------------------------- sr_use_usb = true // True: use USB, false: use ethernet sr_IP = 192.168.2.14 // If sr_use_usb=false, the camera IP sr_grab_grayscale = true // whether to save the intensity channel sr_grab_3d = true // whether to save the 3D points sr_grab_range = true // whether to save the range image sr_grab_confidence = true // whether to save the confidence image // Options for grabber_type= kinect ------------------------------------- kinect_grab_intensity = true // whether to save the intensity (RGB) channel kinect_grab_3d = true // whether to save the 3D points kinect_grab_range = true // whether to save the depth image
Definition at line 182 of file CCameraSensor.h.
#include <mrpt/hwdrivers/CCameraSensor.h>
Public Member Functions | |
CCameraSensor () | |
Constructor The camera is not open until "initialize" is called. | |
virtual | ~CCameraSensor () |
Destructor. | |
void | doProcess () |
This method should be called periodically (at least at 1Hz to capture ALL the real-time data) It is thread safe, i.e. | |
mrpt::slam::CObservationPtr | getNextFrame () |
Retrieves the next frame from the video source, raising an exception on any error. | |
virtual void | initialize () |
Tries to open the camera, after setting all the parameters with a call to loadConfig. | |
void | close () |
Close the camera (if open). | |
virtual void | setPathForExternalImages (const std::string &directory) |
Set the path where to save off-rawlog image files (this class DOES take into account this path). | |
void | enableLaunchOwnThreadForSavingImages (bool enable=true) |
This must be called before initialize() | |
Protected Member Functions | |
void | loadConfig_sensorSpecific (const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection) |
Loads specific configuration for the device from a given source of configuration parameters, for example, an ".ini" file, loading from the section "[iniSection]" (see utils::CConfigFileBase and derived classes) See hwdrivers::CCameraSensor for the possible parameters. | |
Protected Attributes | |
poses::CPose3D | m_sensorPose |
std::string | m_grabber_type |
Can be "opencv",... | |
bool | m_capture_grayscale |
int | m_cv_camera_index |
std::string | m_cv_camera_type |
mrpt::hwdrivers::TCaptureCVOptions | m_cv_options |
uint64_t | m_dc1394_camera_guid |
int | m_dc1394_camera_unit |
mrpt::hwdrivers::TCaptureOptions_dc1394 | m_dc1394_options |
int | m_preview_decimation |
int | m_preview_reduction |
int | m_bumblebee_camera_index |
mrpt::hwdrivers::TCaptureOptions_bumblebee | m_bumblebee_options |
int | m_bumblebee_monocam |
int | m_svs_camera_index |
mrpt::hwdrivers::TCaptureOptions_SVS | m_svs_options |
std::string | m_ffmpeg_url |
std::string | m_rawlog_file |
std::string | m_rawlog_camera_sensor_label |
std::string | m_rawlog_detected_images_dir |
bool | m_sr_open_from_usb |
true: USB, false: ETH | |
std::string | m_sr_ip_address |
bool | m_sr_save_3d |
Save the 3D point cloud (default: true) | |
bool | m_sr_save_range_img |
Save the 2D range image (default: true) | |
bool | m_sr_save_intensity_img |
Save the 2D intensity image (default: true) | |
bool | m_sr_save_confidence |
Save the estimated confidence 2D image (default: false) | |
bool | m_kinect_save_3d |
Save the 3D point cloud (default: true) | |
bool | m_kinect_save_range_img |
Save the 2D range image (default: true) | |
bool | m_kinect_save_intensity_img |
Save the 2D intensity image (default: true) | |
bool | m_external_images_own_thread |
Whether to launch independent thread. | |
Private Attributes | |
CImageGrabber_OpenCV * | m_cap_cv |
The OpenCV capture object. | |
CImageGrabber_dc1394 * | m_cap_dc1394 |
The dc1394 capture object. | |
CStereoGrabber_Bumblebee * | m_cap_bumblebee |
The bumblebee capture object. | |
mrpt::hwdrivers::CStereoGrabber_SVS * | m_cap_svs |
The svs capture object. | |
CFFMPEG_InputStream * | m_cap_ffmpeg |
The FFMPEG capture object. | |
mrpt::utils::CFileGZInputStream * | m_cap_rawlog |
The input file for rawlogs. | |
CSwissRanger3DCamera * | m_cap_swissranger |
SR 3D camera object. | |
CKinect * | m_cap_kinect |
Kinect camera object. | |
int | m_camera_grab_decimator |
int | m_camera_grab_decimator_counter |
int | m_preview_counter |
mrpt::gui::CDisplayWindowPtr | m_preview_win1 |
mrpt::gui::CDisplayWindowPtr | m_preview_win2 |
Normally we'll use only one window, but for stereo images we'll use two of them. | |
Stuff related to working threads to save images to disk | |
unsigned int | m_external_image_saver_count |
Number of working threads. Default:1, set to 2 in quad cores. | |
std::vector < mrpt::system::TThreadHandle > | m_threadImagesSaver |
bool | m_threadImagesSaverShouldEnd |
mrpt::synch::CCriticalSection | m_csToSaveList |
The critical section for m_toSaveList. | |
std::vector< TListObservations > | m_toSaveList |
The queues of objects to be returned by getObservations, one for each working thread. | |
void | thread_save_images (unsigned int my_working_thread_index) |
Thread to save images to files. |
mrpt::hwdrivers::CCameraSensor::CCameraSensor | ( | ) |
Constructor The camera is not open until "initialize" is called.
virtual mrpt::hwdrivers::CCameraSensor::~CCameraSensor | ( | ) | [virtual] |
Destructor.
void mrpt::hwdrivers::CCameraSensor::close | ( | ) |
Close the camera (if open).
This method is called automatically on destruction.
void mrpt::hwdrivers::CCameraSensor::doProcess | ( | ) | [virtual] |
This method should be called periodically (at least at 1Hz to capture ALL the real-time data) It is thread safe, i.e.
you can call this from one thread, then to other methods from other threads.
Implements mrpt::hwdrivers::CGenericSensor.
void mrpt::hwdrivers::CCameraSensor::enableLaunchOwnThreadForSavingImages | ( | bool | enable = true | ) | [inline] |
This must be called before initialize()
Definition at line 226 of file CCameraSensor.h.
mrpt::slam::CObservationPtr mrpt::hwdrivers::CCameraSensor::getNextFrame | ( | ) |
Retrieves the next frame from the video source, raising an exception on any error.
Note: The returned observations can be of one of these classes (you can use IS_CLASS(obs,CObservationXXX) to determine it):
virtual void mrpt::hwdrivers::CCameraSensor::initialize | ( | ) | [virtual] |
Tries to open the camera, after setting all the parameters with a call to loadConfig.
This | method must throw an exception with a descriptive message if some critical error is found. |
Reimplemented from mrpt::hwdrivers::CGenericSensor.
void mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific | ( | const mrpt::utils::CConfigFileBase & | configSource, |
const std::string & | iniSection | ||
) | [protected, virtual] |
Loads specific configuration for the device from a given source of configuration parameters, for example, an ".ini" file, loading from the section "[iniSection]" (see utils::CConfigFileBase and derived classes) See hwdrivers::CCameraSensor for the possible parameters.
Implements mrpt::hwdrivers::CGenericSensor.
virtual void mrpt::hwdrivers::CCameraSensor::setPathForExternalImages | ( | const std::string & | directory | ) | [virtual] |
Set the path where to save off-rawlog image files (this class DOES take into account this path).
An empty string (the default value at construction) means to save images embedded in the rawlog, instead of on separate files.
std::exception | If the directory doesn't exists and cannot be created. |
Reimplemented from mrpt::hwdrivers::CGenericSensor.
void mrpt::hwdrivers::CCameraSensor::thread_save_images | ( | unsigned int | my_working_thread_index | ) | [private] |
Thread to save images to files.
int mrpt::hwdrivers::CCameraSensor::m_bumblebee_camera_index [protected] |
Definition at line 243 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_bumblebee_monocam [protected] |
Definition at line 245 of file CCameraSensor.h.
mrpt::hwdrivers::TCaptureOptions_bumblebee mrpt::hwdrivers::CCameraSensor::m_bumblebee_options [protected] |
Definition at line 244 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_camera_grab_decimator [private] |
Definition at line 288 of file CCameraSensor.h.
Definition at line 289 of file CCameraSensor.h.
The bumblebee capture object.
Definition at line 280 of file CCameraSensor.h.
The OpenCV capture object.
Definition at line 278 of file CCameraSensor.h.
The dc1394 capture object.
Definition at line 279 of file CCameraSensor.h.
The FFMPEG capture object.
Definition at line 282 of file CCameraSensor.h.
Kinect camera object.
Definition at line 285 of file CCameraSensor.h.
The input file for rawlogs.
Definition at line 283 of file CCameraSensor.h.
The svs capture object.
Definition at line 281 of file CCameraSensor.h.
SR 3D camera object.
Definition at line 284 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_capture_grayscale [protected] |
Definition at line 232 of file CCameraSensor.h.
The critical section for m_toSaveList.
Definition at line 300 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_cv_camera_index [protected] |
Definition at line 233 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_cv_camera_type [protected] |
Definition at line 234 of file CCameraSensor.h.
Definition at line 235 of file CCameraSensor.h.
uint64_t mrpt::hwdrivers::CCameraSensor::m_dc1394_camera_guid [protected] |
Definition at line 237 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_dc1394_camera_unit [protected] |
Definition at line 238 of file CCameraSensor.h.
mrpt::hwdrivers::TCaptureOptions_dc1394 mrpt::hwdrivers::CCameraSensor::m_dc1394_options [protected] |
Definition at line 239 of file CCameraSensor.h.
unsigned int mrpt::hwdrivers::CCameraSensor::m_external_image_saver_count [private] |
Number of working threads. Default:1, set to 2 in quad cores.
Definition at line 296 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_external_images_own_thread [protected] |
Whether to launch independent thread.
Definition at line 267 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_ffmpeg_url [protected] |
Definition at line 250 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_grabber_type [protected] |
Can be "opencv",...
Definition at line 231 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_kinect_save_3d [protected] |
Save the 3D point cloud (default: true)
Definition at line 263 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_kinect_save_intensity_img [protected] |
Save the 2D intensity image (default: true)
Definition at line 265 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_kinect_save_range_img [protected] |
Save the 2D range image (default: true)
Definition at line 264 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_preview_counter [private] |
Definition at line 291 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_preview_decimation [protected] |
Definition at line 240 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_preview_reduction [protected] |
Definition at line 241 of file CCameraSensor.h.
Definition at line 292 of file CCameraSensor.h.
Normally we'll use only one window, but for stereo images we'll use two of them.
Definition at line 292 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_rawlog_camera_sensor_label [protected] |
Definition at line 253 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_rawlog_detected_images_dir [protected] |
Definition at line 254 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_rawlog_file [protected] |
Definition at line 252 of file CCameraSensor.h.
Definition at line 226 of file CCameraSensor.h.
std::string mrpt::hwdrivers::CCameraSensor::m_sr_ip_address [protected] |
Definition at line 257 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_sr_open_from_usb [protected] |
true: USB, false: ETH
Definition at line 256 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_sr_save_3d [protected] |
Save the 3D point cloud (default: true)
Definition at line 258 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_sr_save_confidence [protected] |
Save the estimated confidence 2D image (default: false)
Definition at line 261 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_sr_save_intensity_img [protected] |
Save the 2D intensity image (default: true)
Definition at line 260 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_sr_save_range_img [protected] |
Save the 2D range image (default: true)
Definition at line 259 of file CCameraSensor.h.
int mrpt::hwdrivers::CCameraSensor::m_svs_camera_index [protected] |
Definition at line 247 of file CCameraSensor.h.
Definition at line 248 of file CCameraSensor.h.
std::vector<mrpt::system::TThreadHandle> mrpt::hwdrivers::CCameraSensor::m_threadImagesSaver [private] |
Definition at line 297 of file CCameraSensor.h.
bool mrpt::hwdrivers::CCameraSensor::m_threadImagesSaverShouldEnd [private] |
Definition at line 299 of file CCameraSensor.h.
std::vector<TListObservations> mrpt::hwdrivers::CCameraSensor::m_toSaveList [private] |
The queues of objects to be returned by getObservations, one for each working thread.
Definition at line 301 of file CCameraSensor.h.
Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN: at Sat Mar 26 06:40:17 UTC 2011 |