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, PGR FlyCapture,...)
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:
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. Detached threads are created for this task. See setPathForExternalImages() and setExternalImageFormat(). These methods are called automatically from the app rawlog-grabber.
These is the list of all accepted parameters:
bumblebee
driver has been deleted, use the flycap
driver in stereo mode. Definition at line 346 of file CCameraSensor.h.
#include <mrpt/hwdrivers/CCameraSensor.h>
Public Types | |
using | Ptr = std::shared_ptr< CCameraSensor > |
using | TPreSaveUserHook = std::function< void(const mrpt::obs::CObservation::Ptr &obs, void *user_ptr)> |
Functor type. More... | |
enum | TSensorState { ssInitializing = 0, ssWorking, ssError } |
The current state of the sensor. More... | |
typedef std::multimap< mrpt::system::TTimeStamp, mrpt::utils::CSerializable::Ptr > | TListObservations |
typedef std::pair< mrpt::system::TTimeStamp, mrpt::utils::CSerializable::Ptr > | TListObsPair |
Public Member Functions | |
CCameraSensor () | |
Constructor. More... | |
virtual | ~CCameraSensor () |
Destructor. More... | |
void | doProcess () |
This method will be invoked at a minimum rate of "process_rate" (Hz) More... | |
mrpt::obs::CObservation::Ptr | getNextFrame () |
Retrieves the next frame from the video source, raising an exception on any error. More... | |
void | getNextFrame (std::vector< mrpt::utils::CSerializable::Ptr > &out_obs) |
virtual void | initialize () |
Tries to open the camera, after setting all the parameters with a call to loadConfig. More... | |
void | close () |
Close the camera (if open). More... | |
void | setSoftwareTriggerLevel (bool level) |
Set Software trigger level value (ON or OFF) for cameras with this function available. More... | |
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). More... | |
void | enableLaunchOwnThreadForSavingImages (bool enable=true) |
This must be called before initialize() More... | |
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 storage is enabled (e.g. More... | |
virtual const mrpt::hwdrivers::TSensorClassId * | GetRuntimeClass () const =0 |
TSensorState | getState () const |
The current state of the sensor. More... | |
double | getProcessRate () const |
std::string | getSensorLabel () const |
void | setSensorLabel (const std::string &sensorLabel) |
void | enableVerbose (bool enabled=true) |
Enable or disable extra debug info dumped to std::cout during sensor operation. More... | |
bool | isVerboseEnabled () const |
void | loadConfig (const mrpt::utils::CConfigFileBase &configSource, const std::string §ion) |
Loads the generic settings common to any sensor (See CGenericSensor), then call to "loadConfig_sensorSpecific". More... | |
void | getObservations (TListObservations &lstObjects) |
Returns a list of enqueued objects, emptying it (thread-safe). More... | |
void | setExternalImageFormat (const std::string &ext) |
Set the extension ("jpg","gif","png",...) that determines the format of images saved externally The default is "jpg". More... | |
void | setExternalImageJPEGQuality (const unsigned int quality) |
The quality of JPEG compression, when external images is enabled and the format is "jpg". More... | |
unsigned int | getExternalImageJPEGQuality () const |
Static Public Member Functions | |
static void | registerClass (const TSensorClassId *pNewClass) |
Register a class into the internal list of "CGenericSensor" descendents. More... | |
static CGenericSensor * | createSensor (const std::string &className) |
Creates a sensor by a name of the class. More... | |
static CGenericSensor::Ptr | createSensorPtr (const std::string &className) |
Just like createSensor, but returning a smart pointer to the newly created sensor object. More... | |
Protected Member Functions | |
void | loadConfig_sensorSpecific (const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection) |
See the class documentation at the top for expected parameters. More... | |
void | appendObservations (const std::vector< mrpt::utils::CSerializable::Ptr > &obj) |
This method must be called by derived classes to enqueue a new observation in the list to be returned by getObservations. More... | |
void | appendObservation (const mrpt::utils::CSerializable::Ptr &obj) |
Like appendObservations() but for just one observation. More... | |
Private Attributes | |
std::unique_ptr< CImageGrabber_OpenCV > | m_cap_cv |
The OpenCV capture object. More... | |
std::unique_ptr< CImageGrabber_dc1394 > | m_cap_dc1394 |
The dc1394 capture object. More... | |
std::unique_ptr< CImageGrabber_FlyCapture2 > | m_cap_flycap |
The FlyCapture2 object. More... | |
std::unique_ptr< CImageGrabber_FlyCapture2 > | m_cap_flycap_stereo_l |
The FlyCapture2 object for stereo pairs. More... | |
std::unique_ptr< CImageGrabber_FlyCapture2 > | m_cap_flycap_stereo_r |
std::unique_ptr< CStereoGrabber_Bumblebee_libdc1394 > | m_cap_bumblebee_dc1394 |
std::unique_ptr< CStereoGrabber_SVS > | m_cap_svs |
The svs capture object. More... | |
std::unique_ptr< CFFMPEG_InputStream > | m_cap_ffmpeg |
The FFMPEG capture object. More... | |
std::unique_ptr< mrpt::utils::CFileGZInputStream > | m_cap_rawlog |
The input file for rawlogs. More... | |
std::unique_ptr< CSwissRanger3DCamera > | m_cap_swissranger |
SR 3D camera object. More... | |
std::unique_ptr< CKinect > | m_cap_kinect |
Kinect camera object. More... | |
std::unique_ptr< COpenNI2Sensor > | m_cap_openni2 |
OpenNI2 object. More... | |
std::unique_ptr< std::string > | m_cap_image_dir |
Read images from directory. More... | |
std::unique_ptr< CDUO3DCamera > | m_cap_duo3d |
The DUO3D capture object. More... | |
int | m_camera_grab_decimator |
int | m_camera_grab_decimator_counter |
int | m_preview_counter |
mrpt::gui::CDisplayWindow::Ptr | m_preview_win1 |
Normally we'll use only one window, but for stereo images we'll use two of them. More... | |
mrpt::gui::CDisplayWindow::Ptr | m_preview_win2 |
Stuff related to working threads to save images to disk | |
unsigned int | m_external_image_saver_count |
Number of working threads. More... | |
std::vector< std::thread > | m_threadImagesSaver |
bool | m_threadImagesSaverShouldEnd |
std::mutex | m_csToSaveList |
The critical section for m_toSaveList. More... | |
std::vector< TListObservations > | m_toSaveList |
The queues of objects to be returned by getObservations, one for each working thread. More... | |
TPreSaveUserHook | m_hook_pre_save |
void * | m_hook_pre_save_param |
void | thread_save_images (unsigned int my_working_thread_index) |
Thread to save images to files. More... | |
using mrpt::hwdrivers::CCameraSensor::Ptr = std::shared_ptr<CCameraSensor> |
Definition at line 351 of file CCameraSensor.h.
|
inherited |
Definition at line 78 of file CGenericSensor.h.
|
inherited |
Definition at line 80 of file CGenericSensor.h.
using mrpt::hwdrivers::CCameraSensor::TPreSaveUserHook = std::function<void( const mrpt::obs::CObservation::Ptr& obs, void* user_ptr)> |
Functor type.
Definition at line 406 of file CCameraSensor.h.
|
inherited |
The current state of the sensor.
Enumerator | |
---|---|
ssInitializing | |
ssWorking | |
ssError |
Definition at line 85 of file CGenericSensor.h.
CCameraSensor::CCameraSensor | ( | ) |
Constructor.
The camera is not open until "initialize" is called.
Definition at line 40 of file CCameraSensor.cpp.
References mrpt::hwdrivers::CGenericSensor::ssInitializing.
|
virtual |
Destructor.
Definition at line 726 of file CCameraSensor.cpp.
|
inline |
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.) Notice that this code may be called from detached threads, so it must be thread safe. If used, call this before initialize()
Definition at line 414 of file CCameraSensor.h.
References m_hook_pre_save, and m_hook_pre_save_param.
|
inlineprotectedinherited |
Like appendObservations() but for just one observation.
Definition at line 180 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::appendObservations().
Referenced by mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CSwissRanger3DCamera::doProcess(), mrpt::hwdrivers::C2DRangeFinderAbstract::doProcess(), mrpt::hwdrivers::CCANBusReader::doProcess(), mrpt::hwdrivers::CVelodyneScanner::doProcess(), and mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow().
|
protectedinherited |
This method must be called by derived classes to enqueue a new observation in the list to be returned by getObservations.
Passed objects must be created in dynamic memory and a smart pointer passed. Example of creation:
If several observations are passed at once in the vector, they'll be considered as a block regarding the grabbing decimation factor.
Definition at line 53 of file CGenericSensor.cpp.
References CLASS_ID, mrpt::hwdrivers::CGenericSensor::m_csObjList, mrpt::hwdrivers::CGenericSensor::m_grab_decimation, mrpt::hwdrivers::CGenericSensor::m_grab_decimation_counter, mrpt::hwdrivers::CGenericSensor::m_objList, and THROW_EXCEPTION.
Referenced by mrpt::hwdrivers::CGenericSensor::appendObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::doProcess(), and mrpt::hwdrivers::CKinect::doProcess().
void CCameraSensor::close | ( | ) |
Close the camera (if open).
This method is called automatically on destruction.
Definition at line 401 of file CCameraSensor.cpp.
References mrpt::hwdrivers::CGenericSensor::ssInitializing.
|
staticinherited |
Creates a sensor by a name of the class.
Typically the user may want to create a smart pointer around the returned pointer, whis is made with:
Definition at line 103 of file CGenericSensor.cpp.
References mrpt::hwdrivers::CGenericSensor::get_registered_sensor_classes().
Referenced by mrpt::hwdrivers::CGenericSensor::createSensorPtr().
|
inlinestaticinherited |
Just like createSensor, but returning a smart pointer to the newly created sensor object.
Definition at line 220 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::createSensor().
|
virtual |
This method will be invoked at a minimum rate of "process_rate" (Hz)
This | method must throw an exception with a descriptive message if some critical error is found. |
Implements mrpt::hwdrivers::CGenericSensor.
Definition at line 1391 of file CCameraSensor.cpp.
|
inline |
This must be called before initialize()
Definition at line 399 of file CCameraSensor.h.
References m_external_images_own_thread.
|
inlineinherited |
Enable or disable extra debug info dumped to std::cout during sensor operation.
Default: disabled unless the environment variable "MRPT_HWDRIVERS_VERBOSE" is set to "1" during object creation.
Definition at line 106 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_verbose.
|
inlineinherited |
Definition at line 290 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality.
CObservation::Ptr 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):
Definition at line 736 of file CCameraSensor.cpp.
void CCameraSensor::getNextFrame | ( | std::vector< mrpt::utils::CSerializable::Ptr > & | out_obs | ) |
Definition at line 746 of file CCameraSensor.cpp.
References ASSERT_, mrpt::system::fileNameStripInvalidChars(), mrpt::format(), mrpt::utils::IMG_INTERP_NN, IS_CLASS, IS_DERIVED, mrpt::system::now(), mrpt::utils::CImage::scaleImage(), mrpt::hwdrivers::CGenericSensor::ssError, THROW_EXCEPTION, mrpt::system::timeDifference(), mrpt::system::timestampTotime_t(), and mrpt::system::trim().
|
inherited |
Returns a list of enqueued objects, emptying it (thread-safe).
The objects must be freed by the invoker.
Definition at line 91 of file CGenericSensor.cpp.
References mrpt::hwdrivers::CGenericSensor::m_csObjList, and mrpt::hwdrivers::CGenericSensor::m_objList.
|
inlineinherited |
Definition at line 94 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_process_rate.
|
pure virtualinherited |
|
inlineinherited |
Definition at line 95 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.
|
inlineinherited |
The current state of the sensor.
Definition at line 93 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_state.
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.
Definition at line 100 of file CCameraSensor.cpp.
References mrpt::utils::CTypeSelector::checkTypeIndex(), mrpt::format(), mrpt::system::lowerCase(), mrpt::hwdrivers::CGenericSensor::ssError, mrpt::hwdrivers::CGenericSensor::ssWorking, mrpt::hwdrivers::CImageGrabber_FlyCapture2::startSyncCapture(), thread_save_images(), THROW_EXCEPTION, THROW_EXCEPTION_FMT, mrpt::system::trim(), mrpt::system::upperCase(), mrpt::hwdrivers::CKinect::VIDEO_CHANNEL_IR, and mrpt::hwdrivers::CKinect::VIDEO_CHANNEL_RGB.
|
inlineinherited |
Definition at line 107 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_verbose.
|
inherited |
Loads the generic settings common to any sensor (See CGenericSensor), then call to "loadConfig_sensorSpecific".
This | method throws an exception with a descriptive message if some critical parameter is missing or has an invalid value. |
Definition at line 132 of file CGenericSensor.cpp.
References mrpt::hwdrivers::CGenericSensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGenericSensor::m_grab_decimation, mrpt::hwdrivers::CGenericSensor::m_grab_decimation_counter, mrpt::hwdrivers::CGenericSensor::m_max_queue_len, mrpt::hwdrivers::CGenericSensor::m_process_rate, mrpt::hwdrivers::CGenericSensor::m_sensorLabel, MRPT_END, MRPT_START, mrpt::utils::CConfigFileBase::read_double(), mrpt::utils::CConfigFileBase::read_int(), and mrpt::utils::CConfigFileBase::read_string().
|
protectedvirtual |
See the class documentation at the top for expected parameters.
Implements mrpt::hwdrivers::CGenericSensor.
Definition at line 431 of file CCameraSensor.cpp.
References ADD_COLOR_MAP, mrpt::hwdrivers::COLOR_CODING_MONO16, mrpt::hwdrivers::COLOR_CODING_MONO8, mrpt::hwdrivers::COLOR_CODING_RGB8, mrpt::hwdrivers::COLOR_CODING_YUV411, mrpt::hwdrivers::COLOR_CODING_YUV422, mrpt::hwdrivers::COLOR_CODING_YUV444, DEG2RAD, mrpt::hwdrivers::FRAMERATE_120, mrpt::hwdrivers::FRAMERATE_15, mrpt::hwdrivers::FRAMERATE_1_875, mrpt::hwdrivers::FRAMERATE_240, mrpt::hwdrivers::FRAMERATE_30, mrpt::hwdrivers::FRAMERATE_3_75, mrpt::hwdrivers::FRAMERATE_60, mrpt::hwdrivers::FRAMERATE_7_5, MRPT_LOAD_HERE_CONFIG_VAR, mrpt::utils::CConfigFileBase::read_bool(), mrpt::utils::CConfigFileBase::read_double(), mrpt::utils::CConfigFileBase::read_float(), mrpt::utils::CConfigFileBase::read_int(), mrpt::utils::CConfigFileBase::read_string(), mrpt::utils::CConfigFileBase::read_string_first_word(), THROW_EXCEPTION_FMT, mrpt::system::trim(), and mrpt::system::upperCase().
|
staticinherited |
Register a class into the internal list of "CGenericSensor" descendents.
Used internally in the macros DEFINE_GENERIC_SENSOR, etc...
Can be used as "CGenericSensor::registerClass( SENSOR_CLASS_ID(CMySensor) );" if building custom sensors outside mrpt libraries in user code.
Definition at line 121 of file CGenericSensor.cpp.
References mrpt::hwdrivers::TSensorClassId::className, and mrpt::hwdrivers::CGenericSensor::get_registered_sensor_classes().
Referenced by mrpt::hwdrivers::CGenericSensor::CLASSINIT_GENERIC_SENSOR::CLASSINIT_GENERIC_SENSOR().
|
inlineinherited |
Set the extension ("jpg","gif","png",...) that determines the format of images saved externally The default is "jpg".
Definition at line 279 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_external_images_format.
|
inlineinherited |
The quality of JPEG compression, when external images is enabled and the format is "jpg".
Definition at line 286 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality.
|
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.
Definition at line 1421 of file CCameraSensor.cpp.
References mrpt::system::createDirectory(), and THROW_EXCEPTION_FMT.
|
inlineinherited |
Definition at line 96 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.
void CCameraSensor::setSoftwareTriggerLevel | ( | bool | level | ) |
Set Software trigger level value (ON or OFF) for cameras with this function available.
Definition at line 1401 of file CCameraSensor.cpp.
References mrpt::hwdrivers::CGenericSensor::ssError, and THROW_EXCEPTION.
|
private |
Thread to save images to files.
Definition at line 1586 of file CCameraSensor.cpp.
References mrpt::system::fileNameStripInvalidChars(), mrpt::format(), IS_CLASS, IS_DERIVED, mrpt::system::timestampTotime_t(), and mrpt::system::trim().
Referenced by initialize().
|
protected |
Definition at line 442 of file CCameraSensor.h.
|
protected |
Definition at line 443 of file CCameraSensor.h.
|
protected |
Definition at line 444 of file CCameraSensor.h.
|
private |
Definition at line 545 of file CCameraSensor.h.
|
private |
Definition at line 546 of file CCameraSensor.h.
|
private |
Definition at line 526 of file CCameraSensor.h.
|
private |
The OpenCV capture object.
Definition at line 518 of file CCameraSensor.h.
|
private |
The dc1394 capture object.
Definition at line 520 of file CCameraSensor.h.
|
private |
The DUO3D capture object.
Definition at line 542 of file CCameraSensor.h.
|
private |
The FFMPEG capture object.
Definition at line 530 of file CCameraSensor.h.
|
private |
The FlyCapture2 object.
Definition at line 522 of file CCameraSensor.h.
|
private |
The FlyCapture2 object for stereo pairs.
Definition at line 524 of file CCameraSensor.h.
|
private |
Definition at line 524 of file CCameraSensor.h.
|
private |
Read images from directory.
Definition at line 540 of file CCameraSensor.h.
|
private |
Kinect camera object.
Definition at line 536 of file CCameraSensor.h.
|
private |
OpenNI2 object.
Definition at line 538 of file CCameraSensor.h.
|
private |
The input file for rawlogs.
Definition at line 532 of file CCameraSensor.h.
|
private |
The svs capture object.
Definition at line 528 of file CCameraSensor.h.
|
private |
SR 3D camera object.
Definition at line 534 of file CCameraSensor.h.
|
protected |
Definition at line 426 of file CCameraSensor.h.
|
private |
The critical section for m_toSaveList.
Definition at line 561 of file CCameraSensor.h.
|
protected |
Definition at line 429 of file CCameraSensor.h.
|
protected |
Definition at line 430 of file CCameraSensor.h.
|
protected |
Definition at line 431 of file CCameraSensor.h.
|
protected |
Definition at line 434 of file CCameraSensor.h.
|
protected |
Definition at line 435 of file CCameraSensor.h.
|
protected |
Definition at line 436 of file CCameraSensor.h.
|
protected |
Definition at line 504 of file CCameraSensor.h.
|
private |
Number of working threads.
Default:1, set to 2 in quad cores.
Definition at line 556 of file CCameraSensor.h.
|
protectedinherited |
The extension ("jpg","gif","png",...) that determines the format of images saved externally.
Definition at line 158 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), and mrpt::hwdrivers::CGenericSensor::setExternalImageFormat().
|
protectedinherited |
For JPEG images, the quality (default=95%).
Definition at line 160 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::getExternalImageJPEGQuality(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), and mrpt::hwdrivers::CGenericSensor::setExternalImageJPEGQuality().
|
protected |
Whether to launch independent thread.
Definition at line 508 of file CCameraSensor.h.
Referenced by enableLaunchOwnThreadForSavingImages().
|
protected |
Definition at line 489 of file CCameraSensor.h.
|
protected |
Definition at line 451 of file CCameraSensor.h.
|
protected |
Definition at line 485 of file CCameraSensor.h.
|
protected |
Definition at line 491 of file CCameraSensor.h.
|
protectedinherited |
If set to N>=2, only 1 out of N observations will be saved to m_objList.
Definition at line 139 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::appendObservations(), and mrpt::hwdrivers::CGenericSensor::loadConfig().
|
protectedinherited |
Used when "m_grab_decimation" is enabled.
Definition at line 146 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::appendObservations(), and mrpt::hwdrivers::CGenericSensor::loadConfig().
|
protected |
Can be "opencv",...
Definition at line 425 of file CCameraSensor.h.
|
private |
Definition at line 568 of file CCameraSensor.h.
Referenced by addPreSaveHook().
|
private |
Definition at line 569 of file CCameraSensor.h.
Referenced by addPreSaveHook().
|
protected |
Definition at line 501 of file CCameraSensor.h.
|
protected |
Definition at line 498 of file CCameraSensor.h.
|
protected |
Definition at line 500 of file CCameraSensor.h.
|
protected |
Definition at line 495 of file CCameraSensor.h.
|
protected |
Definition at line 496 of file CCameraSensor.h.
|
protected |
Definition at line 497 of file CCameraSensor.h.
|
protected |
Definition at line 494 of file CCameraSensor.h.
|
protected |
Save the 3D point cloud (default: true)
Definition at line 475 of file CCameraSensor.h.
|
protected |
Save the 2D intensity image (default: true)
Definition at line 479 of file CCameraSensor.h.
|
protected |
Save the 2D range image (default: true)
Definition at line 477 of file CCameraSensor.h.
|
protected |
Save RGB or IR channels (default:true)
Definition at line 481 of file CCameraSensor.h.
|
protectedinherited |
See CGenericSensor.
Definition at line 136 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::loadConfig().
|
protectedinherited |
The path where to save off-rawlog images: empty means save images embedded in the rawlog.
Definition at line 155 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CSwissRanger3DCamera::setPathForExternalImages().
|
private |
Definition at line 548 of file CCameraSensor.h.
|
protected |
Definition at line 437 of file CCameraSensor.h.
|
protected |
Definition at line 438 of file CCameraSensor.h.
|
private |
Normally we'll use only one window, but for stereo images we'll use two of them.
Definition at line 551 of file CCameraSensor.h.
|
private |
Definition at line 551 of file CCameraSensor.h.
|
protectedinherited |
See CGenericSensor.
Definition at line 134 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::getProcessRate(), mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), and mrpt::hwdrivers::CGenericSensor::loadConfig().
|
protected |
Definition at line 455 of file CCameraSensor.h.
|
protected |
Definition at line 456 of file CCameraSensor.h.
|
protected |
Definition at line 454 of file CCameraSensor.h.
|
protectedinherited |
See CGenericSensor.
Definition at line 141 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CCANBusReader::CCANBusReader(), mrpt::hwdrivers::CGPSInterface::CGPSInterface(), mrpt::hwdrivers::CGyroKVHDSP3000::CGyroKVHDSP3000(), mrpt::hwdrivers::CHokuyoURG::CHokuyoURG(), mrpt::hwdrivers::CIMUIntersense::CIMUIntersense(), mrpt::hwdrivers::CIMUXSens::CIMUXSens(), mrpt::hwdrivers::CIMUXSens_MT4::CIMUXSens_MT4(), mrpt::hwdrivers::CKinect::CKinect(), mrpt::hwdrivers::CNationalInstrumentsDAQ::CNationalInstrumentsDAQ(), mrpt::hwdrivers::CRoboPeakLidar::CRoboPeakLidar(), mrpt::hwdrivers::CSickLaserSerial::CSickLaserSerial(), mrpt::hwdrivers::CSickLaserUSB::CSickLaserUSB(), mrpt::hwdrivers::CSkeletonTracker::CSkeletonTracker(), mrpt::hwdrivers::CSwissRanger3DCamera::CSwissRanger3DCamera(), mrpt::hwdrivers::CVelodyneScanner::CVelodyneScanner(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CGenericSensor::getSensorLabel(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::hwdrivers::CGenericSensor::loadConfig(), mrpt::hwdrivers::CSkeletonTracker::processPreview(), mrpt::hwdrivers::C2DRangeFinderAbstract::processPreview(), mrpt::hwdrivers::CSkeletonTracker::processPreviewNone(), and mrpt::hwdrivers::CGenericSensor::setSensorLabel().
|
protected |
Definition at line 418 of file CCameraSensor.h.
|
protected |
Definition at line 462 of file CCameraSensor.h.
|
protected |
true: USB, false: ETH
Definition at line 461 of file CCameraSensor.h.
|
protected |
Save the 3D point cloud (default: true)
Definition at line 464 of file CCameraSensor.h.
|
protected |
Save the estimated confidence 2D image (default: false)
Definition at line 470 of file CCameraSensor.h.
|
protected |
Save the 2D intensity image (default: true)
Definition at line 468 of file CCameraSensor.h.
|
protected |
Save the 2D range image (default: true)
Definition at line 466 of file CCameraSensor.h.
|
protectedinherited |
Definition at line 148 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGyroKVHDSP3000::CGyroKVHDSP3000(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CSwissRanger3DCamera::doProcess(), mrpt::hwdrivers::C2DRangeFinderAbstract::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CNationalInstrumentsDAQ::doProcess(), mrpt::hwdrivers::CKinect::doProcess(), mrpt::hwdrivers::CVelodyneScanner::doProcess(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CGenericSensor::getState(), mrpt::hwdrivers::CIMUXSens_MT4::initialize(), mrpt::hwdrivers::CIMUXSens::initialize(), mrpt::hwdrivers::CIMUIntersense::initialize(), mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), mrpt::hwdrivers::CSkeletonTracker::initialize(), mrpt::hwdrivers::CVelodyneScanner::initialize(), mrpt::hwdrivers::CNationalInstrumentsDAQ::readFromDAQ(), and mrpt::hwdrivers::CIMUXSens::searchPortAndConnect().
|
protected |
Definition at line 447 of file CCameraSensor.h.
|
protected |
Definition at line 448 of file CCameraSensor.h.
|
private |
Definition at line 557 of file CCameraSensor.h.
|
private |
Definition at line 559 of file CCameraSensor.h.
|
private |
The queues of objects to be returned by getObservations, one for each working thread.
Definition at line 564 of file CCameraSensor.h.
|
protectedinherited |
Definition at line 149 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::CGenericSensor(), mrpt::hwdrivers::CRoboPeakLidar::checkCOMMs(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CGenericSensor::enableVerbose(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::hwdrivers::CIMUXSens_MT4::initialize(), mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet(), mrpt::hwdrivers::CGenericSensor::isVerboseEnabled(), mrpt::hwdrivers::CGPSInterface::JAVAD_sendMessage(), mrpt::hwdrivers::CGPSInterface::legacy_topcon_setup_commands(), mrpt::hwdrivers::CGPSInterface::OnConnectionEstablished(), mrpt::hwdrivers::CGPSInterface::OnConnectionShutdown(), mrpt::hwdrivers::CNationalInstrumentsDAQ::stop(), and mrpt::hwdrivers::CGPSInterface::tryToOpenTheCOM().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019 |