This "software driver" implements the communication protocol for interfacing a SICK LMS 2XX laser scanners through a standard RS232 serial port (or a USB2SERIAL converter).
The serial port is opened upon the first call to "doProcess" or "initialize", so you must call "loadConfig" before this, or manually call "setSerialPort". Another alternative is to call the base class method C2DRangeFinderAbstract::bindIO, but the "setSerialPort" interface is probably much simpler to use.
For an example of usage see the example in "samples/SICK_laser_serial_test". See also the example configuration file for rawlog-grabber in "share/mrpt/config_files/rawlog-grabber".
Definition at line 70 of file CSickLaserSerial.h.
#include <mrpt/hwdrivers/CSickLaserSerial.h>
Public Types | |
enum | TSensorState { ssInitializing = 0, ssWorking, ssError } |
The current state of the sensor. More... | |
using | Ptr = std::shared_ptr< CGenericSensor > |
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 | |
CSickLaserSerial () | |
Constructor. More... | |
virtual | ~CSickLaserSerial () |
Destructor. More... | |
void | setSerialPort (const std::string &port) |
Changes the serial port to connect to (call prior to 'doProcess'), for example "COM1" or "ttyS0". More... | |
std::string | getSerialPort () const |
void | setBaudRate (int baud) |
Changes the serial port baud rate (call prior to 'doProcess'); valid values are 9600,38400 and 500000. More... | |
int | getBaudRate () const |
void | setMillimeterMode (bool mm_mode=true) |
Enables/Disables the millimeter mode, with a greater accuracy but a shorter range (default=false) (call prior to 'doProcess') This is not needed if the configuration is loaded with "loadConfig". More... | |
void | setScanFOV (int fov_degrees) |
Set the scanning field of view - possible values are 100 or 180 (default) (call prior to 'doProcess') This is not needed if the configuration is loaded with "loadConfig". More... | |
int | getScanFOV () const |
void | setScanResolution (int res_1_100th_degree) |
Set the scanning resolution, in units of 1/100 degree - Possible values are 25, 50 and 100, for 0.25, 0.5 (default) and 1 deg. More... | |
int | getScanResolution () const |
unsigned int | getCurrentConnectTry () const |
If performing several tries in ::initialize(), this is the current try loop number. 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... | |
void | initialize () |
Set-up communication with the laser. 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... | |
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 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 | 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::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... | |
Protected Attributes | |
utils::CStream * | m_stream |
The I/O channel (will be nullptr 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 | tryToOpenComms (std::string *err_msg=nullptr) |
Tries to open the com port and setup all the LMS protocol. More... | |
bool | waitContinuousSampleFrame (std::vector< float > &ranges, unsigned char &LMS_status, bool &is_mm_mode) |
bool | LMS_setupSerialComms () |
Assures laser is connected and operating at 38400, in its case returns true. More... | |
bool | LMS_setupBaudrate (int baud) |
Send a command to change the LMS comms baudrate, return true if ACK is OK. More... | |
bool | LMS_statusQuery () |
Send a status query and wait for the answer. More... | |
bool | LMS_waitACK (uint16_t timeout_ms) |
Returns false if timeout. More... | |
bool | LMS_waitIncomingFrame (uint16_t timeout) |
Returns false if timeout. More... | |
bool | LMS_sendMeasuringMode_cm_mm () |
Returns false on error. More... | |
bool | LMS_startContinuousMode () |
bool | LMS_endContinuousMode () |
bool | SendCommandToSICK (const uint8_t *cmd, const uint16_t cmd_len) |
Send header+command-data+crc and waits for ACK. More... | |
Private Attributes | |
bool | m_mm_mode |
int | m_scans_FOV |
100 or 180 deg More... | |
int | m_scans_res |
1/100th of deg: 100, 50 or 25 More... | |
mrpt::math::TPose3D | m_sensorPose |
The sensor 6D pose: More... | |
uint8_t | m_received_frame_buffer [2000] |
std::string | m_com_port |
If set to non-empty, the serial port will be attempted to be opened automatically when this class is first used to request data from the laser. More... | |
mrpt::comms::CSerialPort * | m_mySerialPort |
Will be !=nullptr only if I created it, so I must destroy it at the end. More... | |
int | m_com_baudRate |
Baudrate: 9600, 38400, 500000. More... | |
unsigned int | m_nTries_connect |
Default = 1. More... | |
unsigned int | m_nTries_current |
bool | m_skip_laser_config |
If true, doesn't send the initialization commands to the laser and go straight to capturing. More... | |
Static Private Attributes | |
static int | CRC16_GEN_POL = 0x8005 |
|
inherited |
Definition at line 73 of file CGenericSensor.h.
|
inherited |
Definition at line 78 of file CGenericSensor.h.
|
inherited |
Definition at line 80 of file CGenericSensor.h.
|
inherited |
The current state of the sensor.
Enumerator | |
---|---|
ssInitializing | |
ssWorking | |
ssError |
Definition at line 85 of file CGenericSensor.h.
CSickLaserSerial::CSickLaserSerial | ( | ) |
Constructor.
Definition at line 42 of file CSickLaserSerial.cpp.
References m_received_frame_buffer, and mrpt::hwdrivers::CGenericSensor::m_sensorLabel.
|
virtual |
Destructor.
Definition at line 60 of file CSickLaserSerial.cpp.
References LMS_endContinuousMode(), m_mySerialPort, m_skip_laser_config, and mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream.
|
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().
|
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 43 of file C2DRangeFinderAbstract.cpp.
References mrpt::hwdrivers::C2DRangeFinderAbstract::m_csChangeStream, and mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream.
Referenced by mrpt::hwdrivers::CHokuyoURG::checkCOMisOpen().
|
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().
|
virtualinherited |
Main method for a CGenericSensor.
Implements mrpt::hwdrivers::CGenericSensor.
Reimplemented in mrpt::hwdrivers::CLMS100Eth.
Definition at line 70 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 86 of file CSickLaserSerial.cpp.
References mrpt::obs::CObservation2DRangeScan::aperture, mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAngles(), mrpt::hwdrivers::C2DRangeFinderAbstract::filterByExclusionAreas(), M_PIf, mrpt::hwdrivers::CGenericSensor::m_sensorLabel, m_sensorPose, mrpt::hwdrivers::CGenericSensor::m_state, mrpt::obs::CObservation2DRangeScan::maxRange, mrpt::system::now(), mrpt::hwdrivers::C2DRangeFinderAbstract::processPreview(), mrpt::obs::CObservation2DRangeScan::resizeScan(), mrpt::obs::CObservation2DRangeScan::rightToLeft, mrpt::obs::CObservation2DRangeScan::scan, 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, tryToOpenComms(), 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 106 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_verbose.
|
protectedinherited |
Mark as invalid those ranges in a set of forbiden angle ranges.
Definition at line 183 of file C2DRangeFinderAbstract.cpp.
References mrpt::obs::CObservation2DRangeScan::filterByExclusionAngles(), and mrpt::hwdrivers::C2DRangeFinderAbstract::m_lstExclusionAngles.
Referenced by mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), and doProcessSimple().
|
protectedinherited |
Mark as invalid those points which (x,y) coordinates fall within the exclusion polygons.
Definition at line 174 of file C2DRangeFinderAbstract.cpp.
References mrpt::obs::CObservation2DRangeScan::filterByExclusionAreas(), and mrpt::hwdrivers::C2DRangeFinderAbstract::m_lstExclusionPolys.
Referenced by mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), and doProcessSimple().
|
inline |
|
inline |
If performing several tries in ::initialize(), this is the current try loop number.
Definition at line 184 of file CSickLaserSerial.h.
References m_nTries_current.
|
inlineinherited |
Definition at line 290 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_external_images_jpeg_quality.
|
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 53 of file C2DRangeFinderAbstract.cpp.
References 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 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 |
|
inline |
Definition at line 171 of file CSickLaserSerial.h.
References m_scans_FOV.
|
inline |
Definition at line 181 of file CSickLaserSerial.h.
References m_scans_res.
|
inlineinherited |
Definition at line 95 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.
|
inline |
|
inlineinherited |
The current state of the sensor.
Definition at line 93 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_state.
Set-up communication with the laser.
Called automatically by rawlog-grabber. If used manually, call after "loadConfig" and before "doProcess".
In this class this method does nothing, since the communications are setup at the first try from "doProcess" or "doProcessSimple".
Reimplemented from mrpt::hwdrivers::CGenericSensor.
Definition at line 391 of file CSickLaserSerial.cpp.
References m_received_frame_buffer, and tryToOpenComms().
|
inlineinherited |
Definition at line 107 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_verbose.
|
private |
Definition at line 758 of file CSickLaserSerial.cpp.
References ASSERT_, LMS_waitIncomingFrame(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, and SendCommandToSICK().
Referenced by LMS_setupSerialComms(), and ~CSickLaserSerial().
|
private |
Returns false on error.
Definition at line 624 of file CSickLaserSerial.cpp.
References ASSERT_, LMS_waitIncomingFrame(), m_mm_mode, m_received_frame_buffer, mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, mrpt::system::os::memcpy(), RET_ERROR, and SendCommandToSICK().
Referenced by tryToOpenComms().
|
private |
Send a command to change the LMS comms baudrate, return true if ACK is OK.
baud can be: 9600, 19200, 38400, 500000
Definition at line 484 of file CSickLaserSerial.cpp.
References ASSERT_, LMS_waitIncomingFrame(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, SendCommandToSICK(), and THROW_EXCEPTION.
Referenced by LMS_setupSerialComms().
|
private |
Assures laser is connected and operating at 38400, in its case returns true.
Definition at line 406 of file CSickLaserSerial.cpp.
References ASSERT_, LMS_endContinuousMode(), LMS_setupBaudrate(), LMS_statusQuery(), m_com_baudRate, m_nTries_connect, m_nTries_current, m_received_frame_buffer, mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, mrpt::comms::CSerialPort::purgeBuffers(), RET_ERROR, and mrpt::comms::CSerialPort::setConfig().
Referenced by tryToOpenComms().
|
private |
Definition at line 724 of file CSickLaserSerial.cpp.
References ASSERT_, LMS_waitIncomingFrame(), m_scans_FOV, m_scans_res, mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, RET_ERROR, and SendCommandToSICK().
Referenced by tryToOpenComms().
|
private |
Send a status query and wait for the answer.
Return true on OK.
Definition at line 518 of file CSickLaserSerial.cpp.
References ASSERT_, LMS_waitIncomingFrame(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, and SendCommandToSICK().
Referenced by LMS_setupSerialComms().
|
private |
Returns false if timeout.
Definition at line 531 of file CSickLaserSerial.cpp.
References ASSERT_, mrpt::format(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, mrpt::comms::CSerialPort::Read(), RET_ERROR, mrpt::utils::CTicTac::Tac(), and mrpt::utils::CTicTac::Tic().
Referenced by SendCommandToSICK().
|
private |
Returns false if timeout.
Definition at line 557 of file CSickLaserSerial.cpp.
References ASSERT_, mrpt::utils::compute_CRC16(), CRC16_GEN_POL, m_received_frame_buffer, mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, mrpt::comms::CSerialPort::Read(), mrpt::utils::CTicTac::Tac(), and mrpt::utils::CTicTac::Tic().
Referenced by LMS_endContinuousMode(), LMS_sendMeasuringMode_cm_mm(), LMS_setupBaudrate(), LMS_startContinuousMode(), and LMS_statusQuery().
|
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 98 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 mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), 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 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 147 of file CSickLaserSerial.cpp.
References DEG2RAD, mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), m_com_baudRate, m_com_port, m_mm_mode, m_nTries_connect, m_scans_FOV, m_scans_res, m_sensorPose, m_skip_laser_config, mrpt::utils::CConfigFileBase::read_bool(), mrpt::utils::CConfigFileBase::read_float(), mrpt::utils::CConfigFileBase::read_int(), and mrpt::utils::CConfigFileBase::read_string().
|
protectedinherited |
Must be called inside the capture method to allow optional GUI preview of scans.
Definition at line 189 of file C2DRangeFinderAbstract.cpp.
References mrpt::hwdrivers::CGenericSensor::m_sensorLabel, mrpt::hwdrivers::C2DRangeFinderAbstract::m_showPreview, mrpt::hwdrivers::C2DRangeFinderAbstract::m_win, and mrpt::opengl::CPlanarLaserScan::setScan().
Referenced by mrpt::hwdrivers::CRoboPeakLidar::doProcessSimple(), mrpt::hwdrivers::CSickLaserUSB::doProcessSimple(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), and 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 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().
Send header+command-data+crc and waits for ACK.
Return false on error.
Definition at line 773 of file CSickLaserSerial.cpp.
References ASSERT_, mrpt::utils::compute_CRC16(), mrpt::obs::gnss::crc, CRC16_GEN_POL, LMS_waitACK(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, mrpt::system::os::memcpy(), and mrpt::comms::CSerialPort::Write().
Referenced by LMS_endContinuousMode(), LMS_sendMeasuringMode_cm_mm(), LMS_setupBaudrate(), LMS_startContinuousMode(), and LMS_statusQuery().
|
inline |
Changes the serial port baud rate (call prior to 'doProcess'); valid values are 9600,38400 and 500000.
This is not needed if the configuration is loaded with "loadConfig".
Definition at line 156 of file CSickLaserSerial.h.
References m_com_baudRate.
|
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.
|
inline |
Enables/Disables the millimeter mode, with a greater accuracy but a shorter range (default=false) (call prior to 'doProcess') This is not needed if the configuration is loaded with "loadConfig".
Definition at line 164 of file CSickLaserSerial.h.
References m_mm_mode.
|
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 268 of file CGenericSensor.h.
References MRPT_UNUSED_PARAM.
|
inline |
Set the scanning field of view - possible values are 100 or 180 (default) (call prior to 'doProcess') This is not needed if the configuration is loaded with "loadConfig".
Definition at line 170 of file CSickLaserSerial.h.
References m_scans_FOV.
|
inline |
Set the scanning resolution, in units of 1/100 degree - Possible values are 25, 50 and 100, for 0.25, 0.5 (default) and 1 deg.
(call prior to 'doProcess') This is not needed if the configuration is loaded with "loadConfig".
Definition at line 177 of file CSickLaserSerial.h.
References m_scans_res.
|
inlineinherited |
Definition at line 96 of file CGenericSensor.h.
References mrpt::hwdrivers::CGenericSensor::m_sensorLabel.
|
inline |
Changes the serial port to connect to (call prior to 'doProcess'), for example "COM1" or "ttyS0".
This is not needed if the configuration is loaded with "loadConfig".
Definition at line 149 of file CSickLaserSerial.h.
References m_com_port.
|
inlineinherited |
Enables GUI visualization in real-time.
Definition at line 120 of file C2DRangeFinderAbstract.h.
References mrpt::hwdrivers::C2DRangeFinderAbstract::m_showPreview.
|
private |
Tries to open the com port and setup all the LMS protocol.
Returns true if OK or already open.
Definition at line 196 of file CSickLaserSerial.cpp.
References ASSERT_, mrpt::comms::CSerialPort::isOpen(), LMS_sendMeasuringMode_cm_mm(), LMS_setupSerialComms(), LMS_startContinuousMode(), m_com_port, m_mySerialPort, m_skip_laser_config, mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, MRPT_LOG_ERROR, mrpt::comms::CSerialPort::open(), RET_ERROR, mrpt::comms::CSerialPort::setConfig(), mrpt::comms::CSerialPort::setSerialPortName(), and mrpt::comms::CSerialPort::setTimeouts().
Referenced by doProcessSimple(), and initialize().
|
virtual |
Disables the scanning mode (in this class this has no effect).
Implements mrpt::hwdrivers::C2DRangeFinderAbstract.
Definition at line 191 of file CSickLaserSerial.cpp.
|
virtual |
Enables the scanning mode (in this class this has no effect).
Implements mrpt::hwdrivers::C2DRangeFinderAbstract.
Definition at line 187 of file CSickLaserSerial.cpp.
|
private |
Definition at line 280 of file CSickLaserSerial.cpp.
References ASSERTMSG_, mrpt::utils::compute_CRC16(), CRC16_GEN_POL, mrpt::format(), mrpt::hwdrivers::C2DRangeFinderAbstract::m_stream, MRPT_LOG_ERROR_FMT, and mrpt::comms::CSerialPort::Read().
Referenced by doProcessSimple().
|
staticprivate |
Definition at line 84 of file CSickLaserSerial.h.
Referenced by LMS_waitIncomingFrame(), SendCommandToSICK(), and waitContinuousSampleFrame().
|
private |
Baudrate: 9600, 38400, 500000.
Definition at line 124 of file CSickLaserSerial.h.
Referenced by getBaudRate(), LMS_setupSerialComms(), loadConfig_sensorSpecific(), and setBaudRate().
|
private |
If set to non-empty, the serial port will be attempted to be opened automatically when this class is first used to request data from the laser.
Definition at line 119 of file CSickLaserSerial.h.
Referenced by getSerialPort(), loadConfig_sensorSpecific(), setSerialPort(), and tryToOpenComms().
|
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().
|
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().
|
protectedinherited |
See CGenericSensor.
Definition at line 136 of file CGenericSensor.h.
Referenced by mrpt::hwdrivers::CGenericSensor::loadConfig().
|
private |
Definition at line 75 of file CSickLaserSerial.h.
Referenced by LMS_sendMeasuringMode_cm_mm(), loadConfig_sensorSpecific(), and setMillimeterMode().
|
private |
Will be !=nullptr only if I created it, so I must destroy it at the end.
Definition at line 122 of file CSickLaserSerial.h.
Referenced by tryToOpenComms(), and ~CSickLaserSerial().
|
private |
Default = 1.
Definition at line 126 of file CSickLaserSerial.h.
Referenced by LMS_setupSerialComms(), and loadConfig_sensorSpecific().
|
private |
Definition at line 127 of file CSickLaserSerial.h.
Referenced by getCurrentConnectTry(), and LMS_setupSerialComms().
|
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().
|
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().
|
private |
Definition at line 114 of file CSickLaserSerial.h.
Referenced by CSickLaserSerial(), initialize(), LMS_sendMeasuringMode_cm_mm(), LMS_setupSerialComms(), and LMS_waitIncomingFrame().
|
private |
100 or 180 deg
Definition at line 77 of file CSickLaserSerial.h.
Referenced by getScanFOV(), LMS_startContinuousMode(), loadConfig_sensorSpecific(), and setScanFOV().
|
private |
1/100th of deg: 100, 50 or 25
Definition at line 79 of file CSickLaserSerial.h.
Referenced by getScanResolution(), LMS_startContinuousMode(), loadConfig_sensorSpecific(), and setScanResolution().
|
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(), 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(), 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().
|
private |
The sensor 6D pose:
Definition at line 82 of file CSickLaserSerial.h.
Referenced by doProcessSimple(), and loadConfig_sensorSpecific().
|
private |
If true, doesn't send the initialization commands to the laser and go straight to capturing.
Definition at line 130 of file CSickLaserSerial.h.
Referenced by loadConfig_sensorSpecific(), tryToOpenComms(), and ~CSickLaserSerial().
|
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(), doProcessSimple(), mrpt::hwdrivers::CGPSInterface::flushParsedMessagesNow(), mrpt::hwdrivers::CVelodyneScanner::getNextObservation(), mrpt::hwdrivers::CGenericSensor::getState(), mrpt::hwdrivers::CIMUXSens_MT4::initialize(), mrpt::hwdrivers::CIMUXSens::initialize(), mrpt::hwdrivers::CGyroKVHDSP3000::initialize(), mrpt::hwdrivers::CIMUIntersense::initialize(), mrpt::hwdrivers::CSkeletonTracker::initialize(), mrpt::hwdrivers::CVelodyneScanner::initialize(), mrpt::hwdrivers::CNationalInstrumentsDAQ::readFromDAQ(), and mrpt::hwdrivers::CIMUXSens::searchPortAndConnect().
|
protectedinherited |
The I/O channel (will be nullptr if not bound).
Definition at line 72 of file C2DRangeFinderAbstract.h.
Referenced by mrpt::hwdrivers::CHokuyoURG::assureBufferHasBytes(), mrpt::hwdrivers::C2DRangeFinderAbstract::bindIO(), mrpt::hwdrivers::CHokuyoURG::checkCOMisOpen(), mrpt::hwdrivers::CHokuyoURG::displaySensorInfo(), mrpt::hwdrivers::CHokuyoURG::displayVersionInfo(), mrpt::hwdrivers::CHokuyoURG::enableSCIP20(), LMS_endContinuousMode(), LMS_sendMeasuringMode_cm_mm(), LMS_setupBaudrate(), LMS_setupSerialComms(), LMS_startContinuousMode(), LMS_statusQuery(), LMS_waitACK(), LMS_waitIncomingFrame(), mrpt::hwdrivers::CHokuyoURG::purgeBuffers(), SendCommandToSICK(), mrpt::hwdrivers::CHokuyoURG::setHighBaudrate(), mrpt::hwdrivers::CHokuyoURG::setHighSensitivityMode(), mrpt::hwdrivers::CHokuyoURG::setMotorSpeed(), mrpt::hwdrivers::CHokuyoURG::startScanningMode(), mrpt::hwdrivers::CHokuyoURG::switchLaserOff(), mrpt::hwdrivers::CHokuyoURG::switchLaserOn(), tryToOpenComms(), mrpt::hwdrivers::CHokuyoURG::turnOn(), waitContinuousSampleFrame(), mrpt::hwdrivers::CHokuyoURG::~CHokuyoURG(), and ~CSickLaserSerial().
|
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 |