23 #define RET_ERROR(msg) { cout << "[" << __CURRENT_FUNCTION_NAME__ <<"] " << msg << endl; return false; } 33 int CSickLaserSerial::CRC16_GEN_POL = 0x8005;
38 CSickLaserSerial::CSickLaserSerial() :
43 m_mySerialPort( NULL ),
44 m_com_baudRate(38400),
47 m_skip_laser_config(false)
81 bool &outThereIsObservation,
85 outThereIsObservation =
false;
86 hardwareError =
false;
95 unsigned char LMS_stat;
118 outObservation.
maxRange = is_mm_mode ? 32.7 : 81.0;
124 for (
size_t i=0;i<ranges.size();i++) {
135 outThereIsObservation =
true;
146 configSource.
read_float(iniSection,
"pose_x",0),
147 configSource.
read_float(iniSection,
"pose_y",0),
148 configSource.
read_float(iniSection,
"pose_z",0),
156 #ifdef MRPT_OS_WINDOWS 196 if (err_msg) *err_msg=
"";
211 throw std::logic_error(
"ERROR: No serial port attached with bindIO, neither it set with 'setSerialPort'");
215 bool just_open =
false;
247 for (
int nTry=0;nTry<4;nTry++)
251 if (!
res)
return false;
253 for (
int nTry=0;nTry<4;nTry++)
265 catch(std::exception &e)
267 std::string s =
"[CSickLaserSerial] Error trying to open SICK at port ";
269 if (err_msg) *err_msg=
s;
279 vector<float> &out_ranges_meters,
280 unsigned char &LMS_status,
284 ASSERTMSG_(COM!=NULL,
"No I/O channel bound to this object");
286 size_t nRead,nBytesToRead;
287 size_t nFrameBytes = 0;
289 unsigned char buf[2000];
290 buf[2]=buf[3]=buf[4]=0;
292 while ( nFrameBytes < (lengthField=( 6 + (buf[2] | (buf[3] << 8))) ) )
304 nBytesToRead = (lengthField) - nFrameBytes;
308 nRead = COM->
Read( buf+nFrameBytes,nBytesToRead );
310 catch (std::exception &e)
313 MRPT_LOG_ERROR_FMT(
"[CSickLaserSerial::waitContinuousSampleFrame] Disconnecting due to comms error: %s\n", e.what());
318 if ( !nRead && !nFrameBytes )
321 if (nRead<nBytesToRead)
326 if (nFrameBytes>1 || (!nFrameBytes && buf[0]==0x02) || (nFrameBytes==1 && buf[1]==0x80))
345 if ( buf[4]!=0xB0 )
return false;
348 int info = buf[5] | (buf[6] << 8);
349 int n_points =
info & 0x01FF;
350 is_mm_mode = 0 != ((
info & 0xC000) >> 14);
352 out_ranges_meters.resize(n_points);
355 short mask = is_mm_mode ? 0x7FFF : 0x1FFF;
356 float meters_scale = is_mm_mode ? 0.001f : 0.01f;
358 for (
int i=0;i<n_points;i++)
359 out_ranges_meters[i] = ( (buf[7+i*2] | (buf[8+i*2] << 8)) &
mask ) * meters_scale;
362 LMS_status = buf[lengthField-3];
366 uint16_t CRC_packet = buf[lengthField-2] | ( buf[lengthField-1] << 8);
369 cerr <<
format(
"[CSickLaserSerial::waitContinuousSampleFrame] bad CRC len=%u nptns=%u: %i != %i",
unsigned(lengthField),
unsigned(n_points), CRC_packet, CRC) << endl;
387 cerr << err_str << endl;
388 throw std::logic_error(err_str);
401 if (COM==NULL)
return true;
403 int detected_rate = 0;
408 int rates[] = {0, 9600,38400,500000};
416 for (
size_t i=0;!detected_rate && i<
sizeof(rates)/
sizeof(rates[0]);i++)
426 for (
int nTry=0;nTry<4 && !detected_rate;nTry++)
432 detected_rate = rates[i];
479 case 9600: cmd[1]=0x42;
break;
480 case 19200: cmd[1]=0x41;
break;
481 case 38400: cmd[1]=0x40;
break;
482 case 500000:cmd[1]=0x48;
break;
523 if ( COM->
Read(&
b,1) )
525 if (
b==0x06)
return true;
528 while ( tictac.
Tac()< timeout_ms*1e-3 );
545 unsigned int nBytes=0;
549 const double maxTime = timeout*1e-3;
553 if ( COM->
Read(&
b,1) )
556 if (nBytes>1 || (!nBytes &&
b==0x02) || (nBytes==1 &&
b==0x80))
563 if (tictac.
Tac()>=maxTime)
569 if (4U+lengthField+2U != nBytes)
571 printf(
"[CSickLaserSerial::LMS_waitIncomingFrame] Error: expected %u bytes, received %u\n",4U+lengthField+2U, nBytes);
580 printf(
"[CSickLaserSerial::LMS_waitIncomingFrame] Error in CRC: rx: 0x%04X, computed: 0x%04X\n",CRC_packet,CRC);
587 for (
unsigned int i=0;i<nBytes;i++)
623 RET_ERROR(
"Wrong response to installation mode");
636 RET_ERROR(
"No expected 0xF4 in response to 0x74 (req. config)");
662 RET_ERROR(
"Wrong answer for config command (0x77)");
674 RET_ERROR(
"Wrong answer for set monitoring mode");
732 ASSERT_(
sizeof(cmd_full)>cmd_len+4U+2U);
740 cmd_full[2] = cmd_len & 0xFF;
741 cmd_full[3] = cmd_len >> 8;
743 memcpy(cmd_full+4,cmd,cmd_len);
746 cmd_full[4+cmd_len+0] =
crc & 0xFF;
747 cmd_full[4+cmd_len+1] =
crc >> 8;
749 const size_t toWrite = 4+cmd_len+2;
753 for (
unsigned int i=0;i<toWrite;i++)
754 printf(
"%02X ",cmd_full[i]);
758 const int NTRIES = 3;
760 for (
int k=0;k<NTRIES;k++)
762 if (toWrite!=COM->
Write( cmd_full, toWrite ))
764 cout <<
"[CSickLaserSerial::SendCommandToSICK] Error writing data to serial port." << endl;
void BASE_IMPEXP memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) MRPT_NO_THROWS
An OS and compiler independent version of "memcpy".
bool LMS_startContinuousMode()
int m_scans_FOV
100 or 180 deg
bool LMS_sendMeasuringMode_cm_mm()
Returns false on error.
CSerialPort * m_mySerialPort
Will be !=NULL only if I created it, so I must destroy it at the end.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
bool isOpen() const
Returns if port has been correctly open.
unsigned __int16 uint16_t
A communications serial port built as an implementation of a utils::CStream.
utils::CStream * m_stream
The I/O channel (will be NULL if not bound).
void setTimeouts(int ReadIntervalTimeout, int ReadTotalTimeoutMultiplier, int ReadTotalTimeoutConstant, int WriteTotalTimeoutMultiplier, int WriteTotalTimeoutConstant)
Changes the timeouts of the port, in milliseconds.
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
bool turnOff()
Disables the scanning mode (in this class this has no effect).
void setScanRange(const size_t i, const float val)
std::string m_sensorLabel
See CGenericSensor.
bool LMS_statusQuery()
Send a status query and wait for the answer. Return true on OK.
#define THROW_EXCEPTION(msg)
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Contains classes for various device interfaces.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
size_t Write(const void *Buffer, size_t Count)
Implements the virtual method responsible for writing to the stream.
int m_com_baudRate
Baudrate: 9600, 38400, 500000.
void filterByExclusionAreas(mrpt::obs::CObservation2DRangeScan &obs) const
Mark as invalid those points which (x,y) coordinates fall within the exclusion polygons.
void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection)
See the class documentation at the top for expected parameters.
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
#define MRPT_LOG_ERROR_FMT(_FMT_STRING,...)
void Tic()
Starts the stopwatch.
void filterByExclusionAngles(mrpt::obs::CObservation2DRangeScan &obs) const
Mark as invalid those ranges in a set of forbiden angle ranges.
bool LMS_setupSerialComms()
Assures laser is connected and operating at 38400, in its case returns true.
This class allows loading and storing values and vectors of different types from a configuration text...
uint8_t m_received_frame_buffer[2000]
float maxRange
The maximum range allowed by the device, in meters (e.g. 80m, 50m,...)
bool LMS_setupBaudrate(int baud)
Send a command to change the LMS comms baudrate, return true if ACK is OK. baud can be: 9600...
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void initialize()
Set-up communication with the laser.
std::string m_com_port
If set to non-empty, the serial port will be attempted to be opened automatically when this class is ...
bool m_skip_laser_config
If true, doesn't send the initialization commands to the laser and go straight to capturing...
bool waitContinuousSampleFrame(std::vector< float > &ranges, unsigned char &LMS_status, bool &is_mm_mode)
void BASE_IMPEXP sleep(int time_ms) MRPT_NO_THROWS
An OS-independent method for sending the current thread to "sleep" for a given period of time...
void setConfig(int baudRate, int parity=0, int bits=8, int nStopBits=1, bool enableFlowControl=false)
Changes the configuration of the port.
This class implements a high-performance stopwatch.
This namespace contains representation of robot actions and observations.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
uint16_t BASE_IMPEXP compute_CRC16(const std::vector< uint8_t > &data, const uint16_t gen_pol=0x8005)
Computes the CRC16 checksum of a block of data.
unsigned int m_nTries_current
bool LMS_waitIncomingFrame(uint16_t timeout)
Returns false if timeout.
mrpt::math::TPose3D m_sensorPose
The sensor 6D pose:
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)...
GLsizei const GLchar ** string
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
virtual ~CSickLaserSerial()
Destructor.
void setSerialPortName(const std::string &COM_name)
Sets the serial port to open (it is an error to try to change this while open yet).
int m_scans_res
1/100th of deg: 100, 50 or 25
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool SendCommandToSICK(const uint8_t *cmd, const uint16_t cmd_len)
Send header+command-data+crc and waits for ACK. Return false on error.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based time...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
void purgeBuffers()
Purge tx and rx buffers.
void open()
Open the port.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
This "software driver" implements the communication protocol for interfacing a SICK LMS 2XX laser sca...
void processPreview(const mrpt::obs::CObservation2DRangeScan &obs)
Must be called inside the capture method to allow optional GUI preview of scans.
double Tac()
Stops the stopwatch.
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
unsigned int m_nTries_connect
Default = 1.
bool turnOn()
Enables the scanning mode (in this class this has no effect).
#define MRPT_LOG_ERROR(_STRING)
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters. Must have same length than validRange.
bool tryToOpenComms(std::string *err_msg=NULL)
Tries to open the com port and setup all the LMS protocol. Returns true if OK or already open...
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...
#define ASSERTMSG_(f, __ERROR_MSG)
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
bool LMS_waitACK(uint16_t timeout_ms)
Returns false if timeout.
bool LMS_endContinuousMode()
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
size_t Read(void *Buffer, size_t Count)
Implements the virtual method responsible for reading from the stream - Unlike CStream::ReadBuffer, this method will not raise an exception on zero bytes read, as long as there is not any fatal error in the communications.
void setScanRangeValidity(const size_t i, const bool val)