sicks3000.cc
Go to the documentation of this file.
00001 /*
00002 *  Copyright (c) 2012, Robotnik Automation, SLL
00003 *
00004 *
00005 *   This program is free software: you can redistribute it and/or modify
00006 *   it under the terms of the GNU General Public License as published by
00007 *   the Free Software Foundation, either version 3 of the License, or
00008 *   (at your option) any later version.
00009 *
00010 *   This program is distributed in the hope that it will be useful,
00011 *   but WITHOUT ANY WARRANTY; without even the implied warranty of
00012 *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013 *   GNU General Public License for more details.
00014 *
00015 *   You should have received a copy of the GNU General Public License
00016 *   along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 *
00018 */
00019 /*
00020  Desc: Driver for the SICK S3000 laser
00021  Author: Robotnik Automation SLL (based on sicks3000 by Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard for Player/Stage)
00022  Date: 1 Sept 2012
00023 
00024  The sicks3000 driver controls the SICK S 3000 safety laser scanner interpreting its data output.
00025  The driver is very basic and assumes the S3000 has already been configured to continuously output
00026  its measured data on the RS422 data lines.
00027 */
00028 
00029 #include <netinet/in.h>  // htons
00030 #include "s3000_laser/sicks3000.h"
00031 
00032 // 1 second of data at 500kbaud
00033 #define DEFAULT_RX_BUFFER_SIZE 500*1024/8
00034 
00036 // Device codes
00037 
00038 #define STX     0x02
00039 #define ACK     0xA0
00040 #define NACK    0x92
00041 #define CRC16_GEN_POL 0x8005
00042 
00044 double DTOR(double val){
00045     return val*3.141592653589793/180.0;
00046 }
00047 
00051 SickS3000::SickS3000( std::string port )
00052 {
00053   rx_count = 0;
00054   // allocate our recieve buffer
00055   rx_buffer_size = DEFAULT_RX_BUFFER_SIZE;
00056   rx_buffer = new uint8_t[rx_buffer_size];
00057   assert(rx_buffer);
00058 
00059   recognisedScanner = false;
00060   mirror = 0;  // TODO move to property
00061 
00062   // Create serial port
00063   serial= new SerialDevice(port.c_str(), S3000_DEFAULT_TRANSFERRATE, S3000_DEFAULT_PARITY, S3000_DEFAULT_DATA_SIZE); //Creates serial device
00064 
00065   return;
00066 }
00067 
00068 SickS3000::~SickS3000() {
00069 
00070   // Close serial port
00071   if (serial!=NULL) serial->ClosePort();
00072 
00073   // Delete serial port
00074   if (serial!=NULL) delete serial;
00075 
00076   delete [] rx_buffer;
00077 }
00078 
00084 int SickS3000::Open(){
00085 
00086         // Setup serial device
00087         if (this->serial->OpenPort2() == SERIAL_ERROR) {
00088           ROS_ERROR("SickS3000::Open: Error Opening Serial Port");
00089           return -1;
00090           }
00091         ROS_INFO("SickS3000::Open: serial port opened at %s", serial->GetDevice());
00092 
00093         return 0;
00094 }
00095 
00101 int SickS3000::Close(){
00102 
00103         if (serial!=NULL) serial->ClosePort();
00104         return 0;
00105 }
00106 
00108 // Set up scanner parameters based on number of results per scan
00109 void SickS3000::SetScannerParams(sensor_msgs::LaserScan& scan, int data_count)
00110 {
00111         if (data_count == 761) // sicks3000
00112         {
00113                 // Scan configuration
00114                 scan.angle_min  = static_cast<float> (DTOR(-95));
00115                 scan.angle_max  = static_cast<float> (DTOR(95));
00116                 scan.angle_increment =  static_cast<float> (DTOR(0.25));
00117                 scan.time_increment = (1.0/16.6) / 761.0;  //(((95.0+95.0)/0.25)+1.0);    // Freq 16.6Hz / 33.3Hz
00118                 scan.scan_time = (1.0/16.6);
00119                 scan.range_min  =  0;
00120                 scan.range_max  =  49;   // check ?
00121 
00122                 recognisedScanner = true;
00123         }
00124 
00125   if (data_count == 541) // sicks30b
00126   {
00127     // Scan configuration
00128     scan.angle_min  = static_cast<float> (DTOR(-135));
00129     scan.angle_max  = static_cast<float> (DTOR(135));
00130     scan.angle_increment =  static_cast<float> (DTOR(0.5));
00131     scan.time_increment = (1.0/12.7) / 541.0;  //(((135.0+135.0)/0.5)+1.0);    // Freq 12.7
00132     scan.scan_time = (1.0/12.7);
00133     scan.range_min  =  0;
00134     scan.range_max  =  40;   // check ? 30m in datasheet
00135 
00136     recognisedScanner = true;
00137   }
00138 }
00139 
00140 void SickS3000::ReadLaser( sensor_msgs::LaserScan& scan, bool& bValidData ) // public periodic function
00141 //void SickS3000::ReadLaser()
00142 {
00143         int read_bytes=0;                       // Number of received bytes
00144         char cReadBuffer[4000] = "\0";          // Max in 1 read
00145 
00146         // Read controller messages
00147         if (serial->ReadPort(cReadBuffer, &read_bytes, 2000)==-1) {
00148             ROS_ERROR("SickS3000::ReadLaser: Error reading port");
00149             }
00150 
00151         unsigned int messageOffset = rx_count;
00152         rx_count += read_bytes;
00153         if (rx_count > rx_buffer_size) {
00154            ROS_WARN("S3000 Buffer Full");
00155            rx_count = 0;
00156            }
00157         else {
00158            memcpy(&rx_buffer[messageOffset], cReadBuffer, read_bytes);
00159            ProcessLaserData(scan, bValidData);
00160            }
00161 }
00162 
00163 
00164 int SickS3000::ProcessLaserData(sensor_msgs::LaserScan& scan, bool& bValidData)
00165 {
00166   while(rx_count >= 22)
00167   {
00168 
00169     // find our continuous data header
00170     unsigned int ii;
00171     bool found = false;
00172     for (ii = 0; ii < rx_count - 22; ++ii)
00173     {
00174       if (memcmp(&rx_buffer[ii],"\0\0\0\0\0\0",6) == 0)
00175       {
00176         memmove(rx_buffer, &rx_buffer[ii], rx_count-ii);
00177         rx_count -= ii;
00178         found = true;
00179         break;
00180       }
00181     }
00182     if (!found)
00183     {
00184       memmove(rx_buffer, &rx_buffer[ii], rx_count-ii);
00185       rx_count -= ii;
00186       return 0;
00187     }
00188 
00189     // get relevant bits of the header
00190     // size includes all data from the data block number
00191     // through to the end of the packet including the checksum
00192     unsigned short size = 2*htons(*reinterpret_cast<unsigned short *> (&rx_buffer[6]));
00193     //ROS_INFO(" size %d   rx_count %d ", size, rx_count);
00194     if (size > rx_buffer_size - 26)
00195     {
00196       ROS_WARN("S3000: Requested Size of data is larger than the buffer size");
00197       memmove(rx_buffer, &rx_buffer[1], --rx_count);
00198       return 0;
00199     }
00200 
00201     // check if we have enough data yet
00202     if (size > rx_count - 4)
00203       return 0;
00204 
00205     unsigned short packet_checksum = *reinterpret_cast<unsigned short *> (&rx_buffer[size+2]);
00206     unsigned short calc_checksum = CreateCRC(&rx_buffer[4], size-2);
00207     if (packet_checksum != calc_checksum)
00208     {
00209       ROS_WARN("S3000: Checksum's dont match, thats bad (data packet size %d)",size);
00210       memmove(rx_buffer, &rx_buffer[1], --rx_count);
00211       continue;
00212     }
00213     else
00214     {
00215       uint8_t * data = &rx_buffer[20];
00216       if (data[0] != data[1])
00217       {
00218         ROS_WARN("S3000: Bad type header bytes dont match");
00219       }
00220       else
00221       {
00222         if (data[0] == 0xAA)
00223         {
00224           ROS_WARN("S3000: We got a I/O data packet we dont know what to do with it\n");
00225         }
00226         else if (data[0] == 0xBB)
00227         {
00228           int data_count = (size - 22) / 2;
00229           if (data_count < 0)
00230           {
00231             ROS_WARN("S3000: bad data count (%d)", data_count);
00232             memmove(rx_buffer, &rx_buffer[size+4], rx_count - (size+4));
00233             rx_count -= (size + 4);
00234             continue;
00235           }
00236           if (!recognisedScanner)
00237             SetScannerParams(scan, data_count); // Set up parameters based on number of results.
00238 
00239           // Scan data, clear ranges, keep configuration
00240           scan.ranges.clear();
00241           scan.intensities.clear();  // not used
00242           // scan.ranges_count = data_count;
00243           scan.ranges.resize(data_count);  //
00244           for (int ii = 0; ii < data_count; ++ii)
00245           {
00246             unsigned short Distance_CM = (*reinterpret_cast<unsigned short *> (&data[4 + 2*ii]));
00247             Distance_CM &= 0x1fff; // remove status bits
00248             double distance_m = static_cast<double>(Distance_CM)/100.0;
00249             if (mirror == 1)
00250                 scan.ranges[data_count - ii - 1] = static_cast<float> (distance_m); // Reverse order.
00251             else
00252                 //scan.ranges.push_back( range );
00253                 scan.ranges[ii] = static_cast<float> (distance_m);
00254           }
00255 
00256           //ROS_INFO("scan.ranges  %5.2f %5.2f %5.2f %5.2f %5.2f %5.2f %5.2f %5.2f ", scan.ranges[200], scan.ranges[201], scan.ranges[202],
00257           //      scan.ranges[203], scan.ranges[204], scan.ranges[205], scan.ranges[206], scan.ranges[207] );
00258 
00259 // CHECK
00260           // Return this flag to let the node know that the message is ready to publish
00261           bValidData = true;
00262         }
00263         else if (data[0] == 0xCC)
00264         {
00265           ROS_WARN("We got a reflector data packet we dont know what to do with it\n");
00266         }
00267         else
00268         {
00269           ROS_WARN("We got an unknown packet\n");
00270         }
00271       }
00272     }
00273 
00274     memmove(rx_buffer, &rx_buffer[size+4], rx_count - (size+4));
00275     rx_count -= (size + 4);
00276     continue;
00277   }
00278   return 1;
00279 }
00280 
00281 
00282 static const unsigned short crc_table[256] = {
00283   0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7,
00284   0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef,
00285   0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6,
00286   0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, 0xf3ff, 0xe3de,
00287   0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485,
00288   0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d,
00289   0x3653, 0x2672, 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4,
00290   0xb75b, 0xa77a, 0x9719, 0x8738, 0xf7df, 0xe7fe, 0xd79d, 0xc7bc,
00291   0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, 0x2802, 0x3823,
00292   0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b,
00293   0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12,
00294   0xdbfd, 0xcbdc, 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a,
00295   0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, 0x2c22, 0x3c03, 0x0c60, 0x1c41,
00296   0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, 0x8d68, 0x9d49,
00297   0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70,
00298   0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78,
00299   0x9188, 0x81a9, 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f,
00300   0x1080, 0x00a1, 0x30c2, 0x20e3, 0x5004, 0x4025, 0x7046, 0x6067,
00301   0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, 0xe37f, 0xf35e,
00302   0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256,
00303   0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d,
00304   0x34e2, 0x24c3, 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
00305   0xa7db, 0xb7fa, 0x8799, 0x97b8, 0xe75f, 0xf77e, 0xc71d, 0xd73c,
00306   0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, 0x4615, 0x5634,
00307   0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab,
00308   0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3,
00309   0xcb7d, 0xdb5c, 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a,
00310   0x4a75, 0x5a54, 0x6a37, 0x7a16, 0x0af1, 0x1ad0, 0x2ab3, 0x3a92,
00311   0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, 0x9de8, 0x8dc9,
00312   0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1,
00313   0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8,
00314   0x6e17, 0x7e36, 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0
00315 };
00316 
00317 unsigned short SickS3000::CreateCRC(uint8_t *Data, ssize_t length)
00318 {
00319   unsigned short CRC_16 = 0xFFFF;
00320   unsigned short i;
00321   for (i = 0; i < length; i++)
00322   {
00323     CRC_16 = (CRC_16 << 8) ^ (crc_table[(CRC_16 >> 8) ^ (Data[i])]);
00324   }
00325   return CRC_16;
00326 }


s3000_laser
Author(s): Román Navarro
autogenerated on Wed Sep 2 2015 11:43:29