A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabber.
Derived classes should be designed with the following execution flow in mind:
Notice that there are helper methods for managing the internal list of objects (see CGenericSensor::appendObservation).
Class Factory: This is also a factory of derived classes, through the static method CGenericSensor::createSensor
For more details on RawLogGrabber refer to the wiki page: http://www.mrpt.org/Application:RawLogGrabber
Definition at line 84 of file CGenericSensor.h.
#include <mrpt/hwdrivers/CGenericSensor.h>
Classes | |
struct | CLASSINIT_GENERIC_SENSOR |
Auxiliary structure used for CSerializable runtime class ID support. More... | |
Public Types | |
enum | TSensorState { ssInitializing = 0, ssWorking, ssError } |
The current state of the sensor. More... | |
typedef std::multimap< mrpt::system::TTimeStamp, mrpt::utils::CSerializablePtr > | TListObservations |
typedef std::pair< mrpt::system::TTimeStamp, mrpt::utils::CSerializablePtr > | TListObsPair |
typedef CGenericSensorPtr | Ptr |
typedef std::shared_ptr< const CGenericSensor > | ConstPtr |
Public Member Functions | |
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 |
CGenericSensor () | |
Constructor. More... | |
virtual | ~CGenericSensor () |
Destructor. More... | |
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... | |
virtual void | initialize () |
This method can or cannot be implemented in the derived class, depending on the need for it. More... | |
virtual void | doProcess ()=0 |
This method will be invoked at a minimum rate of "process_rate" (Hz) More... | |
void | getObservations (TListObservations &lstObjects) |
Returns a list of enqueued objects, emptying it (thread-safe). More... | |
virtual void | setPathForExternalImages (const std::string &directory) |
Set the path where to save off-rawlog image files (will be ignored in those sensors where this is not applicable). 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 CGenericSensorPtr | createSensorPtr (const std::string &className) |
Just like createSensor, but returning a smart pointer to the newly created sensor object. More... | |
Protected Member Functions | |
void | appendObservations (const std::vector< mrpt::utils::CSerializablePtr > &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::CSerializablePtr &obj) |
Like appendObservations() but for just one observation. More... | |
virtual void | loadConfig_sensorSpecific (const mrpt::utils::CConfigFileBase &configSource, const std::string §ion)=0 |
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) More... | |
Protected Attributes | |
size_t | m_grab_decimation_counter |
Used when "m_grab_decimation" is enabled. More... | |
TSensorState | m_state |
bool | m_verbose |
std::string | m_path_for_external_images |
The path where to save off-rawlog images: empty means save images embedded in the rawlog. More... | |
std::string | m_external_images_format |
The extension ("jpg","gif","png",...) that determines the format of images saved externally. More... | |
unsigned int | m_external_images_jpeg_quality |
For JPEG images, the quality (default=95%). More... | |
Common settings to any sensor, loaded in "loadConfig" | |
double | m_process_rate |
See CGenericSensor. More... | |
size_t | m_max_queue_len |
See CGenericSensor. More... | |
size_t | m_grab_decimation |
If set to N>=2, only 1 out of N observations will be saved to m_objList. More... | |
std::string | m_sensorLabel |
See CGenericSensor. More... | |
Private Types | |
typedef std::map< std::string, const TSensorClassId * > | registered_sensor_classes_t |
Used in registerClass. More... | |
Static Private Member Functions | |
static registered_sensor_classes_t & | get_registered_sensor_classes () |
Access to singleton. More... | |
Private Attributes | |
synch::CCriticalSection | m_csObjList |
The critical section for m_objList. More... | |
TListObservations | m_objList |
The queue of objects to be returned by getObservations. More... | |
typedef std::shared_ptr<const CGenericSensor> mrpt::hwdrivers::CGenericSensor::ConstPtr |
Definition at line 124 of file CGenericSensor.h.
Definition at line 123 of file CGenericSensor.h.
|
private |
Used in registerClass.
Definition at line 130 of file CGenericSensor.h.
typedef std::multimap< mrpt::system::TTimeStamp, mrpt::utils::CSerializablePtr > mrpt::hwdrivers::CGenericSensor::TListObservations |
Definition at line 89 of file CGenericSensor.h.
typedef std::pair< mrpt::system::TTimeStamp, mrpt::utils::CSerializablePtr > mrpt::hwdrivers::CGenericSensor::TListObsPair |
Definition at line 90 of file CGenericSensor.h.
The current state of the sensor.
Enumerator | |
---|---|
ssInitializing | |
ssWorking | |
ssError |
Definition at line 95 of file CGenericSensor.h.
CGenericSensor::CGenericSensor | ( | ) |
|
virtual |
|
inlineprotected |
Like appendObservations() but for just one observation.
Definition at line 168 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CSwissRanger3DCamera::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::C2DRangeFinderAbstract::doProcess(), mrpt::hwdrivers::CCANBusReader::doProcess(), mrpt::hwdrivers::CVelodyneScanner::doProcess(), and mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow().
|
protected |
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, m_csObjList, m_grab_decimation, m_grab_decimation_counter, m_objList, and THROW_EXCEPTION.
Referenced by mrpt::hwdrivers::CNationalInstrumentsDAQ::doProcess(), and mrpt::hwdrivers::CKinect::doProcess().
|
static |
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 get_registered_sensor_classes().
|
inlinestatic |
Just like createSensor, but returning a smart pointer to the newly created sensor object.
Definition at line 201 of file CGenericSensor.h.
|
pure 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. |
Implemented in mrpt::hwdrivers::CVelodyneScanner, mrpt::hwdrivers::CCameraSensor, mrpt::hwdrivers::CKinect, mrpt::hwdrivers::COpenNI2Sensor, mrpt::hwdrivers::COpenNI2_RGBD360, mrpt::hwdrivers::CNationalInstrumentsDAQ, mrpt::hwdrivers::CCANBusReader, mrpt::hwdrivers::CGPSInterface, mrpt::hwdrivers::CBoardENoses, mrpt::hwdrivers::C2DRangeFinderAbstract, mrpt::hwdrivers::CEnoseModular, mrpt::hwdrivers::CGyroKVHDSP3000, mrpt::hwdrivers::CIMUIntersense, mrpt::hwdrivers::CNTRIPEmitter, mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::CSkeletonTracker, mrpt::hwdrivers::CLMS100Eth, mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors, mrpt::hwdrivers::CIMUXSens, mrpt::hwdrivers::CIMUXSens_MT4, mrpt::hwdrivers::CImpinjRFID, mrpt::hwdrivers::CBoardSonars, mrpt::hwdrivers::CGPS_NTRIP, mrpt::hwdrivers::CGillAnemometer, mrpt::hwdrivers::CIbeoLuxETH, mrpt::hwdrivers::CRaePID, and mrpt::hwdrivers::CWirelessPower.
|
inline |
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 113 of file CGenericSensor.h.
|
staticprivate |
Access to singleton.
Definition at line 111 of file CGenericSensor.cpp.
Referenced by createSensor(), and registerClass().
|
inline |
Definition at line 255 of file CGenericSensor.h.
void CGenericSensor::getObservations | ( | TListObservations & | lstObjects | ) |
Returns a list of enqueued objects, emptying it (thread-safe).
The objects must be freed by the invoker.
Definition at line 90 of file CGenericSensor.cpp.
References m_csObjList, and m_objList.
|
inline |
Definition at line 105 of file CGenericSensor.h.
|
pure virtual |
|
inline |
Definition at line 107 of file CGenericSensor.h.
|
inline |
The current state of the sensor.
Definition at line 103 of file CGenericSensor.h.
This method can or cannot be implemented in the derived class, depending on the need for it.
This | method must throw an exception with a descriptive message if some critical error is found. |
Reimplemented in mrpt::hwdrivers::CCameraSensor, mrpt::hwdrivers::CVelodyneScanner, mrpt::hwdrivers::CKinect, mrpt::hwdrivers::COpenNI2Sensor, mrpt::hwdrivers::COpenNI2_RGBD360, mrpt::hwdrivers::CNationalInstrumentsDAQ, mrpt::hwdrivers::CSickLaserSerial, mrpt::hwdrivers::CHokuyoURG, mrpt::hwdrivers::CCANBusReader, mrpt::hwdrivers::CBoardENoses, mrpt::hwdrivers::CGyroKVHDSP3000, mrpt::hwdrivers::CIMUIntersense, mrpt::hwdrivers::CSkeletonTracker, mrpt::hwdrivers::CLMS100Eth, mrpt::hwdrivers::CNTRIPEmitter, mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::CIMUXSens, mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors, mrpt::hwdrivers::CIMUXSens_MT4, mrpt::hwdrivers::CImpinjRFID, mrpt::hwdrivers::CGPS_NTRIP, mrpt::hwdrivers::CIbeoLuxETH, and mrpt::hwdrivers::CRoboPeakLidar.
Definition at line 222 of file CGenericSensor.h.
|
inline |
Definition at line 114 of file CGenericSensor.h.
void CGenericSensor::loadConfig | ( | const mrpt::utils::CConfigFileBase & | cfg, |
const std::string & | sect | ||
) |
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 131 of file CGenericSensor.cpp.
References loadConfig_sensorSpecific(), m_grab_decimation, m_grab_decimation_counter, m_max_queue_len, m_process_rate, m_sensorLabel, MRPT_END, MRPT_START, mrpt::utils::CConfigFileBase::read_double(), mrpt::utils::CConfigFileBase::read_int(), and mrpt::utils::CConfigFileBase::read_string().
Referenced by mrpt::hwdrivers::prepareVideoSourceFromPanel(), and mrpt::hwdrivers::prepareVideoSourceFromUserSelection().
|
protectedpure 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)
This | method must throw an exception with a descriptive message if some critical parameter is missing or has an invalid value. |
Implemented in mrpt::hwdrivers::CCameraSensor, mrpt::hwdrivers::CKinect, mrpt::hwdrivers::CNationalInstrumentsDAQ, mrpt::hwdrivers::CHokuyoURG, mrpt::hwdrivers::COpenNI2Sensor, mrpt::hwdrivers::COpenNI2_RGBD360, mrpt::hwdrivers::CGPSInterface, mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::CVelodyneScanner, mrpt::hwdrivers::CLMS100Eth, mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors, mrpt::hwdrivers::CBoardSonars, mrpt::hwdrivers::CSickLaserSerial, mrpt::hwdrivers::CCANBusReader, mrpt::hwdrivers::CIbeoLuxETH, mrpt::hwdrivers::CGyroKVHDSP3000, mrpt::hwdrivers::CRoboPeakLidar, mrpt::hwdrivers::CImpinjRFID, mrpt::hwdrivers::CIMUIntersense, mrpt::hwdrivers::CBoardENoses, mrpt::hwdrivers::CEnoseModular, mrpt::hwdrivers::CGPS_NTRIP, mrpt::hwdrivers::CSkeletonTracker, mrpt::hwdrivers::CSickLaserUSB, mrpt::hwdrivers::CIMUXSens, mrpt::hwdrivers::CNTRIPEmitter, mrpt::hwdrivers::CIMUXSens_MT4, mrpt::hwdrivers::CGillAnemometer, mrpt::hwdrivers::CRaePID, and mrpt::hwdrivers::CWirelessPower.
Referenced by loadConfig().
|
static |
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 120 of file CGenericSensor.cpp.
References mrpt::hwdrivers::TSensorClassId::className, and get_registered_sensor_classes().
Referenced by mrpt::hwdrivers::CGenericSensor::CLASSINIT_GENERIC_SENSOR::CLASSINIT_GENERIC_SENSOR().
|
inline |
Set the extension ("jpg","gif","png",...) that determines the format of images saved externally The default is "jpg".
Definition at line 247 of file CGenericSensor.h.
|
inline |
The quality of JPEG compression, when external images is enabled and the format is "jpg".
Definition at line 252 of file CGenericSensor.h.
References quality.
|
inlinevirtual |
Set the path where to save off-rawlog image files (will be ignored in those sensors where this is not applicable).
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 in mrpt::hwdrivers::CCameraSensor, mrpt::hwdrivers::CKinect, mrpt::hwdrivers::COpenNI2Sensor, mrpt::hwdrivers::COpenNI2_RGBD360, and mrpt::hwdrivers::CSwissRanger3DCamera.
Definition at line 238 of file CGenericSensor.h.
References MRPT_UNUSED_PARAM.
|
inline |
Definition at line 108 of file CGenericSensor.h.
|
private |
The critical section for m_objList.
Definition at line 126 of file CGenericSensor.h.
Referenced by appendObservations(), and getObservations().
|
protected |
The extension ("jpg","gif","png",...) that determines the format of images saved externally.
Definition at line 152 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific().
|
protected |
For JPEG images, the quality (default=95%).
Definition at line 153 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific().
|
protected |
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 appendObservations(), and loadConfig().
|
protected |
Used when "m_grab_decimation" is enabled.
Definition at line 144 of file CGenericSensor.h.
Referenced by appendObservations(), and loadConfig().
|
protected |
|
private |
The queue of objects to be returned by getObservations.
Definition at line 127 of file CGenericSensor.h.
Referenced by appendObservations(), getObservations(), and ~CGenericSensor().
|
protected |
The path where to save off-rawlog images: empty means save images embedded in the rawlog.
Definition at line 151 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CSwissRanger3DCamera::setPathForExternalImages().
|
protected |
See CGenericSensor.
Definition at line 137 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), and loadConfig().
|
protected |
See CGenericSensor.
Definition at line 140 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::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CCANBusReader::doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CKinect::getNextObservation(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), loadConfig(), mrpt::hwdrivers::CSkeletonTracker::processPreview(), mrpt::hwdrivers::C2DRangeFinderAbstract::processPreview(), and mrpt::hwdrivers::CSkeletonTracker::processPreviewNone().
|
protected |
Definition at line 146 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGyroKVHDSP3000::CGyroKVHDSP3000(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CSkeletonTracker::doProcess(), mrpt::hwdrivers::CSwissRanger3DCamera::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::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::CSickLaserSerial::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CIMUXSens_MT4::initialize(), mrpt::hwdrivers::CIMUXSens::initialize(), mrpt::hwdrivers::CSkeletonTracker::initialize(), mrpt::hwdrivers::CIMUIntersense::initialize(), mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), mrpt::hwdrivers::CVelodyneScanner::initialize(), mrpt::hwdrivers::CNationalInstrumentsDAQ::readFromDAQ(), and mrpt::hwdrivers::CIMUXSens::searchPortAndConnect().
|
protected |
Definition at line 147 of file CGenericSensor.h.
Referenced by CGenericSensor(), mrpt::hwdrivers::CRoboPeakLidar::checkCOMMs(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), mrpt::hwdrivers::CNationalInstrumentsDAQ::grabbing_thread(), mrpt::hwdrivers::CIMUXSens_MT4::initialize(), mrpt::hwdrivers::CHokuyoURG::initialize(), mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet(), 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.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |