Class CGenericSensor

Inheritance Relationships

Derived Types

Class Documentation

class CGenericSensor

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:

  • Object constructor

  • CGenericSensor::loadConfig: The following parameters are common to all sensors in rawlog-grabber (they are automatically loaded by rawlog-grabber) - see each class documentation for additional parameters:

    • ”process_rate”: (Mandatory) The rate in Hertz (Hz) at which the sensor thread should invoke “doProcess”.

    • ”max_queue_len”: (Optional) The maximum number of objects in the observations queue (default is 200). If overflow occurs, an error message will be issued at run-time.

    • ”grab_decimation”: (Optional) Grab only 1 out of N observations captured by the sensor (default is 1, i.e. do not decimate).

  • CGenericSensor::initialize

  • CGenericSensor::doProcess

  • CGenericSensor::getObservations

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: https://www.mrpt.org/Application:RawLogGrabber

Subclassed by mrpt::hwdrivers::C2DRangeFinderAbstract, mrpt::hwdrivers::CCANBusReader, mrpt::hwdrivers::CCameraSensor, mrpt::hwdrivers::CEnoseModular, mrpt::hwdrivers::CGPSInterface, mrpt::hwdrivers::CGPS_NTRIP, mrpt::hwdrivers::CGillAnemometer, mrpt::hwdrivers::CGyroKVHDSP3000, mrpt::hwdrivers::CIMUXSens_MT4, mrpt::hwdrivers::CIbeoLuxETH, mrpt::hwdrivers::CImpinjRFID, mrpt::hwdrivers::CKinect, mrpt::hwdrivers::CNTRIPEmitter, mrpt::hwdrivers::CNationalInstrumentsDAQ, mrpt::hwdrivers::COpenNI2Sensor, mrpt::hwdrivers::COpenNI2_RGBD360, mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors, mrpt::hwdrivers::CRaePID, mrpt::hwdrivers::CTaoboticsIMU, mrpt::hwdrivers::CVelodyneScanner, mrpt::hwdrivers::CWirelessPower

Common settings to any sensor, loaded in “loadConfig”

double m_process_rate = {0}

See CGenericSensor

size_t m_max_queue_len = {200}

See CGenericSensor

size_t m_grab_decimation = {0}

If set to N>=2, only 1 out of N observations will be saved to m_objList.

std::string m_sensorLabel = "UNNAMED_SENSOR"

See CGenericSensor

Public Types

enum TSensorState

The current state of the sensor

Values:

enumerator ssInitializing
enumerator ssWorking
enumerator ssError
enumerator ssUninitialized
using Ptr = std::shared_ptr<CGenericSensor>
using TListObservations = std::multimap<mrpt::system::TTimeStamp, mrpt::serialization::CSerializable::Ptr>
using TListObsPair = std::pair<mrpt::system::TTimeStamp, mrpt::serialization::CSerializable::Ptr>

Public Functions

virtual const mrpt::hwdrivers::TSensorClassId *GetRuntimeClass() const = 0
inline TSensorState getState() const

The current state of the sensor

inline double getProcessRate() const
inline std::string getSensorLabel() const
inline void setSensorLabel(const std::string &sensorLabel)
inline void enableVerbose(bool enabled = true)

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.

inline bool isVerboseEnabled() const
CGenericSensor()

Constructor

CGenericSensor(const CGenericSensor&) = delete
CGenericSensor &operator=(const CGenericSensor&) = delete
virtual ~CGenericSensor()

Destructor

virtual void loadConfig(const mrpt::config::CConfigFileBase &configSource, const std::string &section)

Loads the generic settings common to any sensor (See CGenericSensor), then call to “loadConfig_sensorSpecific”

Throws:

This – method throws an exception with a descriptive message if some critical parameter is missing or has an invalid value.

inline virtual void initialize()

This method can or cannot be implemented in the derived class, depending on the need for it.

Throws:

This – method must throw an exception with a descriptive message if some critical error is found.

virtual void doProcess() = 0

This method will be invoked at a minimum rate of “process_rate” (Hz)

Throws:

This – method must throw an exception with a descriptive message if some critical error is found.

virtual TListObservations getObservations()

Returns a list of enqueued objects, emptying it (thread-safe).

inline virtual void setPathForExternalImages([[maybe_unused]] 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). An empty string (the default value at construction) means to save images embedded in the rawlog, instead of on separate files.

Throws:

std::exception – If the directory doesn’t exists and cannot be created.

inline virtual void setExternalImageFormat(const std::string &ext)

Set the extension (“jpg”,”gif”,”png”,…) that determines the format of images saved externally. Default: “png”.

inline virtual void setExternalImageJPEGQuality(const unsigned int quality)

The quality of JPEG compression, when external images is enabled and the format is “jpg”.

inline virtual unsigned int getExternalImageJPEGQuality() const

Public Static Functions

static void registerClass(const TSensorClassId *pNewClass)

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.

static CGenericSensor *createSensor(const std::string &className)

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:

  CGenericSensor::Ptr sensor = CGenericSensor::Ptr(
CGenericSensor::createSensor("XXX") );

Returns:

A pointer to a new class, or nullptr if class name is unknown.

static inline Ptr createSensorPtr(const std::string &className)

Just like createSensor, but returning a smart pointer to the newly created sensor object.

Protected Functions

void appendObservations(const std::vector<mrpt::serialization::CSerializable::Ptr> &obj)

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:

  mrpt::obs::CObservationGPS::Ptr  o = CObservationGPS::Ptr( new
CObservationGPS() );
  o-> .... // Set data
  appendObservation(o);
If several observations are passed at once in the vector, they’ll be considered as a block regarding the grabbing decimation factor.

inline void appendObservation(const mrpt::serialization::CSerializable::Ptr &obj)

Like appendObservations() but for just one observation.

virtual void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &section) = 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 config::CConfigFileBase and derived classes)

Throws:

This – method must throw an exception with a descriptive message if some critical parameter is missing or has an invalid value.

Protected Attributes

size_t m_grab_decimation_counter = {0}

Used when “m_grab_decimation” is enabled

TSensorState m_state = {ssInitializing}
bool m_verbose = {false}
std::string m_path_for_external_images

The path where to save off-rawlog images: empty means save images embedded in the rawlog.

std::string m_external_images_format = "png"

The extension (“jpg”,”gif”,”png”,…) that determines the format of images saved externally

unsigned int m_external_images_jpeg_quality = {95}

For JPEG images, the quality (default=95%).