MRPT  2.0.0
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
mrpt::hwdrivers::CGyroKVHDSP3000 Class Referenceabstract

Detailed Description

A class for interfacing KVH DSP 3000 gyroscope with an assynchronous serial communication (product SN : 02-1222-01).

It uses a serial port connection to the device. The class implements the generic sensor class. See also the application "rawlog-grabber" for a ready-to-use application to gather data from the scanner. The generated observation is a CObservationIMU, but only the yaw angular velocity and the absolute yaw position are are set in the vector CObservationIMU::rawMeasurements. The sensor process rate is imposed by hardware at 100Hz. For now, this sensor is only supported on posix system.

PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
-------------------------------------------------------
[supplied_section_name]
process_rate = 100 ; MUST be 100 Hz.
pose_x=0 ; Sensor 3D position relative to the robot (meters)
pose_y=0
pose_z=0
pose_yaw=0 ; Angles in degrees
pose_pitch=0
pose_roll=0
sensorLabel = <label> ; Label of the sensor
COM_port_LIN = /dev/ttyUSB0 ; COM PORT in LINUX
operatingMode = <"rate"/"integrated", "incremental"> ; Default mode is
*Rate.

In most of the communs applications, this class will be used as :

/// ...
CConfigFile conf("conf.ini");
/// ...
kvh.loadConfig_sensorSpecific(conf, "KVH");
/// ...
while(1) {
kvh.doProcess();
kvh.getObservations(rateObs);
// ....

Definition at line 69 of file CGyroKVHDSP3000.h.

#include <mrpt/hwdrivers/CGyroKVHDSP3000.h>

Inheritance diagram for mrpt::hwdrivers::CGyroKVHDSP3000:

Public Types

enum  TSensorState { ssInitializing = 0, ssWorking, ssError, ssUninitialized }
 The current state of the sensor. More...
 
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 Member Functions

 CGyroKVHDSP3000 ()
 Constructor. More...
 
void loadConfig_sensorSpecific (const mrpt::config::CConfigFileBase &configSource, const std::string &iniSection) override
 See the class documentation at the top for expected parameters. More...
 
 ~CGyroKVHDSP3000 () override
 Destructor. More...
 
void doProcess () override
 This method will be invoked at a minimum rate of "process_rate" (Hz) More...
 
void initialize () override
 Turns on the KVH DSP 3000 device and configure it for getting orientation data. More...
 
void resetIncrementalAngle ()
 Send to the sensor the command 'Z' wich reset the integrated angle. More...
 
void changeMode (GYRO_MODE _newMode)
 
virtual const mrpt::hwdrivers::TSensorClassIdGetRuntimeClass () 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::config::CConfigFileBase &configSource, const std::string &section)
 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...
 
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). 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 CGenericSensorcreateSensor (const std::string &className)
 Creates a sensor by a name of the class. More...
 
static 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 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. More...
 
void appendObservation (const mrpt::serialization::CSerializable::Ptr &obj)
 Like appendObservations() but for just one observation. More...
 

Protected Attributes

int m_COMbauds {38400}
 This serial port will be attempted to be opened automatically when this class is first used to request data from the device. More...
 
std::string m_com_port
 
mrpt::poses::CPose3D m_sensorPose
 
std::unique_ptr< mrpt::comms::CSerialPortm_serialPort
 Search the port where the sensor is located and connect to it. More...
 
GYRO_MODE m_mode {RATE}
 
bool m_firstInteration {true}
 
mrpt::obs::CObservationIMU::Ptr m_observationGyro
 
size_t m_grab_decimation_counter {0}
 Used when "m_grab_decimation" is enabled. More...
 
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. 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 {95}
 For JPEG images, the quality (default=95%). More...
 
Common settings to any sensor, loaded in "loadConfig"
double m_process_rate {0}
 See CGenericSensor. More...
 
size_t m_max_queue_len {200}
 See CGenericSensor. More...
 
size_t m_grab_decimation {0}
 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...
 

Member Typedef Documentation

◆ Ptr

Definition at line 73 of file CGenericSensor.h.

◆ TListObservations

Definition at line 77 of file CGenericSensor.h.

◆ TListObsPair

Definition at line 79 of file CGenericSensor.h.

Member Enumeration Documentation

◆ TSensorState

The current state of the sensor.

See also
CGenericSensor::getState
Enumerator
ssInitializing 
ssWorking 
ssError 
ssUninitialized 

Definition at line 84 of file CGenericSensor.h.

Constructor & Destructor Documentation

◆ CGyroKVHDSP3000()

CGyroKVHDSP3000::CGyroKVHDSP3000 ( )

◆ ~CGyroKVHDSP3000()

CGyroKVHDSP3000::~CGyroKVHDSP3000 ( )
override

Destructor.

Definition at line 35 of file CGyroKVHDSP3000.cpp.

References m_serialPort.

Member Function Documentation

◆ appendObservation()

void mrpt::hwdrivers::CGenericSensor::appendObservation ( const mrpt::serialization::CSerializable::Ptr obj)
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(), 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ appendObservations()

void CGenericSensor::appendObservations ( const std::vector< mrpt::serialization::CSerializable::Ptr > &  obj)
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:

mrpt::obs::CObservationGPS::Ptr o = CObservationGPS::Ptr( new
CObservationGPS() );
o-> .... // Set data

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 48 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().

Here is the caller graph for this function:

◆ changeMode()

void CGyroKVHDSP3000::changeMode ( GYRO_MODE  _newMode)

Definition at line 142 of file CGyroKVHDSP3000.cpp.

References mrpt::hwdrivers::INCREMENTAL_ANGLE, mrpt::hwdrivers::INTEGRATED_ANGLE, m_mode, m_serialPort, mrpt::hwdrivers::RATE, and THROW_EXCEPTION.

Referenced by initialize().

Here is the caller graph for this function:

◆ createSensor()

CGenericSensor * CGenericSensor::createSensor ( const std::string &  className)
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:

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

Definition at line 97 of file CGenericSensor.cpp.

References mrpt::hwdrivers::CGenericSensor::get_registered_sensor_classes().

Referenced by mrpt::hwdrivers::CGenericSensor::createSensorPtr().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ createSensorPtr()

static Ptr mrpt::hwdrivers::CGenericSensor::createSensorPtr ( const std::string &  className)
inlinestaticinherited

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

Definition at line 210 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::createSensor().

Referenced by mrpt::apps::RawlogGrabberApp::SensorThread().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ doProcess()

void CGyroKVHDSP3000::doProcess ( )
overridevirtual

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

Exceptions
Thismethod must throw an exception with a descriptive message if some critical error is found.

Implements mrpt::hwdrivers::CGenericSensor.

Definition at line 40 of file CGyroKVHDSP3000.cpp.

References mrpt::hwdrivers::CGenericSensor::appendObservation(), mrpt::DEG2RAD(), mrpt::obs::IMU_YAW, mrpt::obs::IMU_YAW_VEL, mrpt::hwdrivers::INCREMENTAL_ANGLE, initialize(), mrpt::hwdrivers::INTEGRATED_ANGLE, m_firstInteration, m_mode, mrpt::hwdrivers::CGenericSensor::m_sensorLabel, m_sensorPose, m_serialPort, mrpt::hwdrivers::CGenericSensor::m_state, mrpt::system::now(), mrpt::hwdrivers::RATE, mrpt::hwdrivers::CGenericSensor::ssError, and mrpt::system::tokenize().

Here is the call graph for this function:

◆ enableVerbose()

void mrpt::hwdrivers::CGenericSensor::enableVerbose ( bool  enabled = true)
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.

◆ getExternalImageJPEGQuality()

unsigned int mrpt::hwdrivers::CGenericSensor::getExternalImageJPEGQuality ( ) const
inlineinherited

◆ getObservations()

void CGenericSensor::getObservations ( TListObservations lstObjects)
inherited

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

The objects must be freed by the invoker.

Definition at line 85 of file CGenericSensor.cpp.

References mrpt::hwdrivers::CGenericSensor::m_csObjList, and mrpt::hwdrivers::CGenericSensor::m_objList.

Referenced by TEST().

Here is the caller graph for this function:

◆ getProcessRate()

double mrpt::hwdrivers::CGenericSensor::getProcessRate ( ) const
inlineinherited

Definition at line 94 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_process_rate.

◆ GetRuntimeClass()

virtual const mrpt::hwdrivers::TSensorClassId* mrpt::hwdrivers::CGenericSensor::GetRuntimeClass ( ) const
pure virtualinherited

◆ getSensorLabel()

std::string mrpt::hwdrivers::CGenericSensor::getSensorLabel ( ) const
inlineinherited

Definition at line 95 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.

◆ getState()

TSensorState mrpt::hwdrivers::CGenericSensor::getState ( ) const
inlineinherited

The current state of the sensor.

Definition at line 93 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_state.

◆ initialize()

void CGyroKVHDSP3000::initialize ( )
overridevirtual

Turns on the KVH DSP 3000 device and configure it for getting orientation data.

you must have called loadConfig_sensorSpecific before calling this function.

Reimplemented from mrpt::hwdrivers::CGenericSensor.

Definition at line 88 of file CGyroKVHDSP3000.cpp.

References changeMode(), m_com_port, m_COMbauds, m_mode, mrpt::hwdrivers::CGenericSensor::m_process_rate, m_serialPort, mrpt::hwdrivers::CGenericSensor::m_state, resetIncrementalAngle(), mrpt::hwdrivers::CGenericSensor::ssWorking, and THROW_EXCEPTION.

Referenced by doProcess().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isVerboseEnabled()

bool mrpt::hwdrivers::CGenericSensor::isVerboseEnabled ( ) const
inlineinherited

Definition at line 107 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_verbose.

◆ loadConfig()

void CGenericSensor::loadConfig ( const mrpt::config::CConfigFileBase cfg,
const std::string &  sect 
)
inherited

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

Exceptions
Thismethod throws an exception with a descriptive message if some critical parameter is missing or has an invalid value.

Definition at line 126 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::config::CConfigFileBase::read_double(), mrpt::config::CConfigFileBase::read_int(), mrpt::config::CConfigFileBase::read_string(), and sect.

Here is the call graph for this function:

◆ loadConfig_sensorSpecific()

void CGyroKVHDSP3000::loadConfig_sensorSpecific ( const mrpt::config::CConfigFileBase configSource,
const std::string &  iniSection 
)
overridevirtual

See the class documentation at the top for expected parameters.

Implements mrpt::hwdrivers::CGenericSensor.

Definition at line 109 of file CGyroKVHDSP3000.cpp.

References mrpt::DEG2RAD(), mrpt::hwdrivers::INCREMENTAL_ANGLE, mrpt::hwdrivers::INTEGRATED_ANGLE, m_com_port, m_mode, m_sensorPose, mrpt::hwdrivers::RATE, mrpt::config::CConfigFileBase::read_float(), mrpt::config::CConfigFileBase::read_string(), and mrpt::poses::CPose3D::setFromValues().

Here is the call graph for this function:

◆ registerClass()

void CGenericSensor::registerClass ( const TSensorClassId pNewClass)
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 115 of file CGenericSensor.cpp.

References mrpt::hwdrivers::TSensorClassId::className, and mrpt::hwdrivers::CGenericSensor::get_registered_sensor_classes().

Here is the call graph for this function:

◆ resetIncrementalAngle()

void CGyroKVHDSP3000::resetIncrementalAngle ( )

Send to the sensor the command 'Z' wich reset the integrated angle.

(in both rate mode and incremental, this function has no effect)

Definition at line 168 of file CGyroKVHDSP3000.cpp.

References m_mode, m_serialPort, mrpt::hwdrivers::RATE, and THROW_EXCEPTION.

Referenced by initialize().

Here is the caller graph for this function:

◆ setExternalImageFormat()

void mrpt::hwdrivers::CGenericSensor::setExternalImageFormat ( const std::string &  ext)
inlineinherited

Set the extension ("jpg","gif","png",...) that determines the format of images saved externally The default is "jpg".

See also
setPathForExternalImages, setExternalImageJPEGQuality

Definition at line 268 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_external_images_format.

◆ setExternalImageJPEGQuality()

void mrpt::hwdrivers::CGenericSensor::setExternalImageJPEGQuality ( const unsigned int  quality)
inlineinherited

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

See also
setExternalImageFormat

Definition at line 275 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality.

◆ setPathForExternalImages()

virtual void mrpt::hwdrivers::CGenericSensor::setPathForExternalImages ( [ [maybe_unused] ] const std::string &  directory)
inlinevirtualinherited

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.

Exceptions
std::exceptionIf the directory doesn't exists and cannot be created.

Definition at line 257 of file CGenericSensor.h.

◆ setSensorLabel()

void mrpt::hwdrivers::CGenericSensor::setSensorLabel ( const std::string &  sensorLabel)
inlineinherited

Definition at line 96 of file CGenericSensor.h.

References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.

Member Data Documentation

◆ m_com_port

std::string mrpt::hwdrivers::CGyroKVHDSP3000::m_com_port
protected

Definition at line 78 of file CGyroKVHDSP3000.h.

Referenced by initialize(), and loadConfig_sensorSpecific().

◆ m_COMbauds

int mrpt::hwdrivers::CGyroKVHDSP3000::m_COMbauds {38400}
protected

This serial port will be attempted to be opened automatically when this class is first used to request data from the device.

See also
comms::CSerialPort

Definition at line 77 of file CGyroKVHDSP3000.h.

Referenced by initialize().

◆ m_external_images_format

std::string mrpt::hwdrivers::CGenericSensor::m_external_images_format
protectedinherited

The extension ("jpg","gif","png",...) that determines the format of images saved externally.

See also
setPathForExternalImages

Definition at line 158 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), and mrpt::hwdrivers::CGenericSensor::setExternalImageFormat().

◆ m_external_images_jpeg_quality

unsigned int mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality {95}
protectedinherited

◆ m_firstInteration

bool mrpt::hwdrivers::CGyroKVHDSP3000::m_firstInteration {true}
protected

Definition at line 89 of file CGyroKVHDSP3000.h.

Referenced by doProcess().

◆ m_grab_decimation

size_t mrpt::hwdrivers::CGenericSensor::m_grab_decimation {0}
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().

◆ m_grab_decimation_counter

size_t mrpt::hwdrivers::CGenericSensor::m_grab_decimation_counter {0}
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().

◆ m_max_queue_len

size_t mrpt::hwdrivers::CGenericSensor::m_max_queue_len {200}
protectedinherited

See CGenericSensor.

Definition at line 136 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CGenericSensor::loadConfig().

◆ m_mode

GYRO_MODE mrpt::hwdrivers::CGyroKVHDSP3000::m_mode {RATE}
protected

◆ m_observationGyro

mrpt::obs::CObservationIMU::Ptr mrpt::hwdrivers::CGyroKVHDSP3000::m_observationGyro
protected

Definition at line 91 of file CGyroKVHDSP3000.h.

◆ m_path_for_external_images

std::string mrpt::hwdrivers::CGenericSensor::m_path_for_external_images
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().

◆ m_process_rate

double mrpt::hwdrivers::CGenericSensor::m_process_rate {0}
protectedinherited

◆ m_sensorLabel

std::string mrpt::hwdrivers::CGenericSensor::m_sensorLabel
protectedinherited

See CGenericSensor.

Definition at line 141 of file CGenericSensor.h.

Referenced by mrpt::hwdrivers::CCANBusReader::CCANBusReader(), mrpt::hwdrivers::CGPSInterface::CGPSInterface(), CGyroKVHDSP3000(), mrpt::hwdrivers::CHokuyoURG::CHokuyoURG(), 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(), doProcess(), mrpt::hwdrivers::CSkeletonTracker::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::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().

◆ m_sensorPose

mrpt::poses::CPose3D mrpt::hwdrivers::CGyroKVHDSP3000::m_sensorPose
protected

Definition at line 80 of file CGyroKVHDSP3000.h.

Referenced by doProcess(), and loadConfig_sensorSpecific().

◆ m_serialPort

std::unique_ptr<mrpt::comms::CSerialPort> mrpt::hwdrivers::CGyroKVHDSP3000::m_serialPort
protected

Search the port where the sensor is located and connect to it.

The serial port connection

Definition at line 87 of file CGyroKVHDSP3000.h.

Referenced by changeMode(), doProcess(), initialize(), resetIncrementalAngle(), and ~CGyroKVHDSP3000().

◆ m_state

TSensorState mrpt::hwdrivers::CGenericSensor::m_state {ssInitializing}
protectedinherited

◆ m_verbose

bool mrpt::hwdrivers::CGenericSensor::m_verbose {false}
protectedinherited



Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020