This "software driver" implements the communication protocol for interfacing a SICK LMS2XX laser scanners through a custom USB RS-422 interface board.
NOTE that this class is for a custom hardware built at our lab (MAPIR, University of Malaga). For a generic serial interface, see the class CSickLaserSerial.
This class does not need to be bind, i.e. you do not need to call C2DRangeFinderAbstract::bindIO. However, calling it will have not effect. In this class the "bind" is ignored since it is designed for USB connections only, thus it internally generate the required object for simplicity of use. The serial number of the USB device is used to open it on the first call to "doProcess", thus you must call "loadConfig" before this, or manually call "setDeviceSerialNumber". The default serial number is "LASER001"
Warning: Avoid defining an object of this class in a global scope if you want to catch all potential exceptions during the constructors (like USB interface DLL not found, etc...)
Definition at line 57 of file CSickLaserUSB.h.
#include <mrpt/hwdrivers/CSickLaserUSB.h>
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 | |
CSickLaserUSB () | |
Constructor. More... | |
virtual | ~CSickLaserUSB () |
Destructor. More... | |
void | setDeviceSerialNumber (const std::string &deviceSerialNumber) |
Changes the serial number of the device to open (call prior to 'doProcess') More... | |
void | doProcessSimple (bool &outThereIsObservation, mrpt::obs::CObservation2DRangeScan &outObservation, bool &hardwareError) |
Specific laser scanner "software drivers" must process here new data from the I/O stream, and, if a whole scan has arrived, return it. More... | |
bool | turnOn () |
Enables the scanning mode (in this class this has no effect). More... | |
bool | turnOff () |
Disables the scanning mode (in this class this has no effect). More... | |
void | showPreview (bool enable=true) |
Enables GUI visualization in real-time. More... | |
void | bindIO (mrpt::utils::CStream *streamIO) |
Binds the object to a given I/O channel. More... | |
void | getObservation (bool &outThereIsObservation, mrpt::obs::CObservation2DRangeScan &outObservation, bool &hardwareError) |
Get the last observation from the sensor, if available, and unmarks it as being "the last one" (thus a new scan must arrive or subsequent calls will find no new observations). More... | |
void | doProcess () |
Main method for a CGenericSensor. 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... | |
virtual void | initialize () |
This method can or cannot be implemented in the derived class, depending on the need for it. 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 | loadConfig_sensorSpecific (const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection) |
See the class documentation at the top for expected parameters. More... | |
void | loadCommonParams (const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection) |
Should be call by derived classes at "loadConfig" (loads exclusion areas AND exclusion angles). More... | |
void | filterByExclusionAreas (mrpt::obs::CObservation2DRangeScan &obs) const |
Mark as invalid those points which (x,y) coordinates fall within the exclusion polygons. More... | |
void | filterByExclusionAngles (mrpt::obs::CObservation2DRangeScan &obs) const |
Mark as invalid those ranges in a set of forbiden angle ranges. More... | |
void | processPreview (const mrpt::obs::CObservation2DRangeScan &obs) |
Must be called inside the capture method to allow optional GUI preview of scans. More... | |
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... | |
Protected Attributes | |
utils::CStream * | m_stream |
The I/O channel (will be NULL if not bound). More... | |
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 Member Functions | |
bool | checkControllerIsConnected () |
bool | waitContinuousSampleFrame (std::vector< float > &ranges, unsigned char &LMS_status, uint32_t &out_board_timestamp, bool &is_mm_mode) |
Private Attributes | |
CInterfaceFTDI * | m_usbConnection |
std::string | m_serialNumber |
uint32_t | m_timeStartUI |
Time of the first data packet, for synchronization purposes. More... | |
mrpt::system::TTimeStamp | m_timeStartTT |
poses::CPose3D | m_sensorPose |
The sensor 6D pose: More... | |
|
inherited |
Definition at line 124 of file CGenericSensor.h.
|
inherited |
Definition at line 123 of file CGenericSensor.h.
|
inherited |
Definition at line 89 of file CGenericSensor.h.
|
inherited |
Definition at line 90 of file CGenericSensor.h.
|
inherited |
The current state of the sensor.
Enumerator | |
---|---|
ssInitializing | |
ssWorking | |
ssError |
Definition at line 95 of file CGenericSensor.h.
CSickLaserUSB::CSickLaserUSB | ( | ) |
Constructor.
Definition at line 36 of file CSickLaserUSB.cpp.
References mrpt::hwdrivers::CGenericSensor::m_sensorLabel, m_usbConnection, MRPT_END, and MRPT_START.
|
virtual |
|
inlineprotectedinherited |
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().
|
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::CNationalInstrumentsDAQ::doProcess(), and mrpt::hwdrivers::CKinect::doProcess().
|
inherited |
Binds the object to a given I/O channel.
The stream object must not be deleted before the destruction of this class.
Definition at line 46 of file C2DRangeFinderAbstract.cpp.
References mrpt::synch::CCriticalSection::enter(), mrpt::synch::CCriticalSection::leave(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_csChangeStream, and mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream.
Referenced by mrpt::hwdrivers::CHokuyoURG::ensureStreamIsOpen().
|
private |
Definition at line 166 of file CSickLaserUSB.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::isOpen(), m_serialNumber, m_usbConnection, MRPT_LOG_ERROR_FMT, MRPT_LOG_INFO_FMT, mrpt::hwdrivers::CInterfaceFTDI::OpenBySerialNumber(), mrpt::hwdrivers::CInterfaceFTDI::ResetDevice(), mrpt::hwdrivers::CInterfaceFTDI::SetLatencyTimer(), mrpt::hwdrivers::CInterfaceFTDI::SetTimeouts(), and mrpt::system::sleep().
Referenced by doProcessSimple().
|
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().
|
inlinestaticinherited |
Just like createSensor, but returning a smart pointer to the newly created sensor object.
Definition at line 201 of file CGenericSensor.h.
|
virtualinherited |
Main method for a CGenericSensor.
Implements mrpt::hwdrivers::CGenericSensor.
Reimplemented in mrpt::hwdrivers::CLMS100Eth.
Definition at line 75 of file C2DRangeFinderAbstract.cpp.
References mrpt::hwdrivers::CGenericSensor::appendObservation(), mrpt::hwdrivers::C2DRangeFinderAbstract::doProcessSimple(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_nextObservation, mrpt::hwdrivers::CGenericSensor::m_state, mrpt::hwdrivers::CGenericSensor::ssError, mrpt::hwdrivers::CGenericSensor::ssWorking, and THROW_EXCEPTION.
|
virtual |
Specific laser scanner "software drivers" must process here new data from the I/O stream, and, if a whole scan has arrived, return it.
This method will be typically called in a different thread than other methods, and will be called in a timely fashion.
Implements mrpt::hwdrivers::C2DRangeFinderAbstract.
Definition at line 59 of file CSickLaserUSB.cpp.
References mrpt::obs::CObservation2DRangeScan::aperture, checkControllerIsConnected(), mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAngles(), mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAreas(), M_PIf, mrpt::hwdrivers::CGenericSensor::m_sensorLabel, m_sensorPose, mrpt::hwdrivers::CGenericSensor::m_state, m_timeStartTT, m_timeStartUI, mrpt::obs::CObservation2DRangeScan::maxRange, mrpt::system::now(), mrpt::hwdrivers::C2DRangeFinderAbstract::processPreview(), mrpt::obs::CObservation2DRangeScan::resizeScan(), mrpt::obs::CObservation2DRangeScan::rightToLeft, mrpt::system::secondsToTimestamp(), mrpt::obs::CObservation::sensorLabel, mrpt::obs::CObservation2DRangeScan::sensorPose, mrpt::obs::CObservation2DRangeScan::setScanRange(), mrpt::obs::CObservation2DRangeScan::setScanRangeValidity(), mrpt::hwdrivers::CGenericSensor::ssWorking, mrpt::obs::CObservation2DRangeScan::stdError, mrpt::obs::CObservation::timestamp, and waitContinuousSampleFrame().
|
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 113 of file CGenericSensor.h.
|
protectedinherited |
Mark as invalid those ranges in a set of forbiden angle ranges.
Definition at line 174 of file C2DRangeFinderAbstract.cpp.
References mrpt::obs::CObservation2DRangeScan::filterByExclusionAngles(), and mrpt::hwdrivers::C2DRangeFinderAbstract::m_lstExclusionAngles.
Referenced by mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), and mrpt::hwdrivers::CHokuyoURG::doProcessSimple().
|
protectedinherited |
Mark as invalid those points which (x,y) coordinates fall within the exclusion polygons.
Definition at line 166 of file C2DRangeFinderAbstract.cpp.
References mrpt::obs::CObservation2DRangeScan::filterByExclusionAreas(), and mrpt::hwdrivers::C2DRangeFinderAbstract::m_lstExclusionPolys.
Referenced by mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), and mrpt::hwdrivers::CHokuyoURG::doProcessSimple().
|
inlineinherited |
Definition at line 255 of file CGenericSensor.h.
|
inherited |
Get the last observation from the sensor, if available, and unmarks it as being "the last one" (thus a new scan must arrive or subsequent calls will find no new observations).
Definition at line 56 of file C2DRangeFinderAbstract.cpp.
References mrpt::synch::CCriticalSection::enter(), mrpt::synch::CCriticalSection::leave(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_csLastObservation, mrpt::hwdrivers::C2DRangeFinderAbstract::m_hardwareError, mrpt::hwdrivers::C2DRangeFinderAbstract::m_lastObservation, and mrpt::hwdrivers::C2DRangeFinderAbstract::m_lastObservationIsNew.
|
inherited |
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 mrpt::hwdrivers::CGenericSensor::m_csObjList, and mrpt::hwdrivers::CGenericSensor::m_objList.
|
inlineinherited |
Definition at line 105 of file CGenericSensor.h.
|
pure virtualinherited |
|
inlineinherited |
Definition at line 107 of file CGenericSensor.h.
|
inlineinherited |
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.
|
inlineinherited |
Definition at line 114 of file CGenericSensor.h.
|
protectedinherited |
Should be call by derived classes at "loadConfig" (loads exclusion areas AND exclusion angles).
This loads a sequence of vertices of a polygon given by its (x,y) coordinates relative to the vehicle, that is, taking into account the "sensorPose".
The number of zones is variable, but they must start at 1 and be consecutive.
This also loads any other common params (e.g. 'preview')
Definition at line 102 of file C2DRangeFinderAbstract.cpp.
References ASSERT_, ASSERTMSG_, DEG2RAD, mrpt::format(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_lstExclusionAngles, mrpt::hwdrivers::C2DRangeFinderAbstract::m_lstExclusionPolys, M_PI, mrpt::hwdrivers::C2DRangeFinderAbstract::m_showPreview, mrpt::utils::CConfigFileBase::read_bool(), mrpt::utils::CConfigFileBase::read_double(), and mrpt::utils::CConfigFileBase::read_vector().
Referenced by loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), and mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific().
|
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 131 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().
Referenced by mrpt::hwdrivers::prepareVideoSourceFromPanel(), and mrpt::hwdrivers::prepareVideoSourceFromUserSelection().
|
protectedvirtual |
See the class documentation at the top for expected parameters.
Implements mrpt::hwdrivers::CGenericSensor.
Definition at line 130 of file CSickLaserUSB.cpp.
References DEG2RAD, mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), m_sensorPose, m_serialNumber, mrpt::utils::CConfigFileBase::read_float(), and mrpt::utils::CConfigFileBase::read_string().
|
protectedinherited |
Must be called inside the capture method to allow optional GUI preview of scans.
Definition at line 180 of file C2DRangeFinderAbstract.cpp.
References mrpt::opengl::CPlanarLaserScan::Create(), mrpt::gui::CDisplayWindow3D::Create(), mrpt::hwdrivers::CGenericSensor::m_sensorLabel, mrpt::hwdrivers::C2DRangeFinderAbstract::m_showPreview, and mrpt::hwdrivers::C2DRangeFinderAbstract::m_win.
Referenced by mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), doProcessSimple(), mrpt::hwdrivers::CSickLaserSerial::doProcessSimple(), and mrpt::hwdrivers::CHokuyoURG::doProcessSimple().
|
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 120 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().
|
inline |
Changes the serial number of the device to open (call prior to 'doProcess')
Definition at line 92 of file CSickLaserUSB.h.
|
inlineinherited |
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.
|
inlineinherited |
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.
|
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.
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.
|
inlineinherited |
Definition at line 108 of file CGenericSensor.h.
|
inlineinherited |
Enables GUI visualization in real-time.
Definition at line 95 of file C2DRangeFinderAbstract.h.
|
virtual |
Disables the scanning mode (in this class this has no effect).
Implements mrpt::hwdrivers::C2DRangeFinderAbstract.
Definition at line 158 of file CSickLaserUSB.cpp.
|
virtual |
Enables the scanning mode (in this class this has no effect).
Implements mrpt::hwdrivers::C2DRangeFinderAbstract.
Definition at line 150 of file CSickLaserUSB.cpp.
|
private |
Definition at line 196 of file CSickLaserUSB.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::compute_CRC16(), mrpt::format(), info, m_timeStartUI, m_usbConnection, MRPT_LOG_ERROR_FMT, and mrpt::hwdrivers::CInterfaceFTDI::ReadSync().
Referenced by doProcessSimple().
|
protectedinherited |
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().
|
protectedinherited |
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().
|
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 144 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::appendObservations(), and mrpt::hwdrivers::CGenericSensor::loadConfig().
|
protectedinherited |
See CGenericSensor.
Definition at line 138 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 151 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CSwissRanger3DCamera::getNextObservation(), and mrpt::hwdrivers::CSwissRanger3DCamera::setPathForExternalImages().
|
protectedinherited |
See CGenericSensor.
Definition at line 137 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), and mrpt::hwdrivers::CGenericSensor::loadConfig().
|
protectedinherited |
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(), 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(), 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(), mrpt::hwdrivers::CGenericSensor::loadConfig(), mrpt::hwdrivers::CSkeletonTracker::processPreview(), mrpt::hwdrivers::C2DRangeFinderAbstract::processPreview(), and mrpt::hwdrivers::CSkeletonTracker::processPreviewNone().
|
private |
The sensor 6D pose:
Definition at line 70 of file CSickLaserUSB.h.
Referenced by doProcessSimple(), and loadConfig_sensorSpecific().
|
private |
Definition at line 63 of file CSickLaserUSB.h.
Referenced by checkControllerIsConnected(), and loadConfig_sensorSpecific().
|
protectedinherited |
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(), 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().
|
protectedinherited |
The I/O channel (will be NULL if not bound).
Definition at line 58 of file C2DRangeFinderAbstract.h.
Referenced by mrpt::hwdrivers::CHokuyoURG::assureBufferHasBytes(), mrpt::hwdrivers::C2DRangeFinderAbstract::bindIO(), mrpt::hwdrivers::CHokuyoURG::ensureStreamIsOpen(), mrpt::hwdrivers::CSickLaserSerial::LMS_endContinuousMode(), mrpt::hwdrivers::CSickLaserSerial::LMS_sendMeasuringMode_cm_mm(), mrpt::hwdrivers::CSickLaserSerial::LMS_setupBaudrate(), mrpt::hwdrivers::CSickLaserSerial::LMS_setupSerialComms(), mrpt::hwdrivers::CSickLaserSerial::LMS_startContinuousMode(), mrpt::hwdrivers::CSickLaserSerial::LMS_statusQuery(), mrpt::hwdrivers::CSickLaserSerial::LMS_waitACK(), mrpt::hwdrivers::CSickLaserSerial::LMS_waitIncomingFrame(), mrpt::hwdrivers::CHokuyoURG::purgeBuffers(), mrpt::hwdrivers::CHokuyoURG::sendCmd(), mrpt::hwdrivers::CSickLaserSerial::SendCommandToSICK(), mrpt::hwdrivers::CSickLaserSerial::tryToOpenComms(), mrpt::hwdrivers::CHokuyoURG::turnOn(), mrpt::hwdrivers::CSickLaserSerial::waitContinuousSampleFrame(), mrpt::hwdrivers::CHokuyoURG::~CHokuyoURG(), and mrpt::hwdrivers::CSickLaserSerial::~CSickLaserSerial().
|
private |
Definition at line 66 of file CSickLaserUSB.h.
Referenced by doProcessSimple().
|
private |
Time of the first data packet, for synchronization purposes.
Definition at line 65 of file CSickLaserUSB.h.
Referenced by doProcessSimple(), and waitContinuousSampleFrame().
|
private |
Definition at line 62 of file CSickLaserUSB.h.
Referenced by checkControllerIsConnected(), CSickLaserUSB(), waitContinuousSampleFrame(), and ~CSickLaserUSB().
|
protectedinherited |
Definition at line 147 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::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.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |