ScannerSickS300.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2010
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering   
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_driver
00012  * ROS package name: cob_sick_s300
00013  * Description:
00014  *                                                              
00015  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016  *                      
00017  * Author: Christian Connette, email:christian.connette@ipa.fhg.de
00018  * Supervised by: Christian Connette, email:christian.connette@ipa.fhg.de
00019  *
00020  * Date of creation: Jan 2009
00021  * ToDo:
00022  *
00023  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00024  *
00025  * Redistribution and use in source and binary forms, with or without
00026  * modification, are permitted provided that the following conditions are met:
00027  *
00028  *     * Redistributions of source code must retain the above copyright
00029  *       notice, this list of conditions and the following disclaimer.
00030  *     * Redistributions in binary form must reproduce the above copyright
00031  *       notice, this list of conditions and the following disclaimer in the
00032  *       documentation and/or other materials provided with the distribution.
00033  *     * Neither the name of the Fraunhofer Institute for Manufacturing 
00034  *       Engineering and Automation (IPA) nor the names of its
00035  *       contributors may be used to endorse or promote products derived from
00036  *       this software without specific prior written permission.
00037  *
00038  * This program is free software: you can redistribute it and/or modify
00039  * it under the terms of the GNU Lesser General Public License LGPL as 
00040  * published by the Free Software Foundation, either version 3 of the 
00041  * License, or (at your option) any later version.
00042  * 
00043  * This program is distributed in the hope that it will be useful,
00044  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00045  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00046  * GNU Lesser General Public License LGPL for more details.
00047  * 
00048  * You should have received a copy of the GNU Lesser General Public 
00049  * License LGPL along with this program. 
00050  * If not, see <http://www.gnu.org/licenses/>.
00051  *
00052  ****************************************************************/
00053 
00054 #include <cob_sick_s300/ScannerSickS300.h>
00055 
00056 #include <stdint.h>
00057 #include <arpa/inet.h>
00058 
00059 //-----------------------------------------------
00060 
00061 typedef unsigned char BYTE;
00062 
00063 const double ScannerSickS300::c_dPi = 3.14159265358979323846;
00064 unsigned char ScannerSickS300::m_iScanId = 7;
00065 
00066 const unsigned short crc_LookUpTable[256]
00067            = { 
00068            0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, 
00069            0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, 
00070            0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, 
00071            0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE, 
00072            0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485, 
00073            0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D, 
00074            0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4, 
00075            0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC, 
00076            0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823, 
00077            0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B, 
00078            0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, 
00079            0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A, 
00080            0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, 
00081            0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49, 
00082            0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70, 
00083            0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78, 
00084            0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F, 
00085            0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067, 
00086            0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, 
00087            0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256, 
00088            0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, 
00089            0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, 
00090            0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C, 
00091            0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634, 
00092            0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB, 
00093            0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3, 
00094            0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A, 
00095            0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92, 
00096            0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, 
00097            0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1, 
00098            0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, 
00099            0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0 
00100          }; 
00101 
00102 class TelegramParser {
00103 
00104         #pragma pack(push,1)
00105         union TELEGRAM_COMMON {
00106                 struct {
00107                         uint32_t reply_telegram;
00108                         uint16_t trigger_result;
00109                         uint16_t size;
00110                         uint8_t  coordination_flag;
00111                         uint8_t  device_addresss;
00112                         uint16_t protocol_version;
00113                         uint16_t status;
00114                         uint32_t scan_number;
00115                         uint16_t telegram_number;
00116                         uint16_t type;
00117                 };
00118                 uint8_t bytes[22];
00119         };
00120 
00121         union TELEGRAM_DISTANCE {
00122                 struct {
00123                         uint16_t type;
00124                 };
00125                 uint8_t bytes[2];
00126         };
00127 
00128         union TELEGRAM_TAIL {
00129                 struct {
00130                         uint16_t crc;
00131                 };
00132                 uint8_t bytes[2];
00133         };
00134 
00135         union TELEGRAM_S300_DIST_2B {
00136                 struct {
00137                         unsigned distance : 13; //cm
00138                         unsigned bit13 : 1;  //reflector or scanner distorted
00139                         unsigned protective : 1;
00140                         unsigned warn_field : 1;
00141                 };
00142                 uint8_t bytes[2];
00143         };
00144 
00145         #pragma pack(pop)
00146 
00147         enum TELEGRAM_COMMON_HS {JUNK_SIZE=4};
00148         enum TELEGRAM_COMMON_TYPES {IO=0xAAAA, DISTANCE=0xBBBB, REFLEXION=0xCCCC};
00149         enum TELEGRAM_DIST_SECTOR {_1=0x1111, _2=0x2222, _3=0x3333, _4=0x4444, _5=0x5555};
00150 
00151 
00152         static void ntoh(TELEGRAM_COMMON &tc) {
00153                 tc.reply_telegram = ntohl(tc.reply_telegram);
00154                 tc.trigger_result = ntohs(tc.trigger_result);
00155                 tc.size = ntohs(tc.size);
00156                 tc.protocol_version = ntohs(tc.protocol_version);
00157                 tc.status = ntohs(tc.status);
00158                 tc.scan_number = ntohl(tc.scan_number);
00159                 tc.telegram_number = ntohs(tc.telegram_number);
00160                 tc.type = ntohs(tc.type);
00161         }
00162 
00163         static void ntoh(TELEGRAM_DISTANCE &tc) {
00164                 tc.type = ntohs(tc.type);
00165         }
00166 
00167         static void ntoh(TELEGRAM_TAIL &tc) {
00168             //crc calc. is also in network order
00169                 //tc.crc = ntohs(tc.crc);
00170         }
00171 
00172         static void print(const TELEGRAM_COMMON &tc) {
00173                 std::cout<<"HEADER"<<std::endl;
00174                 std::cout<<"reply_telegram"<<":"<<tc.reply_telegram<<std::endl;
00175                 std::cout<<"trigger_result"<<":"<<tc.trigger_result<<std::endl;
00176                 std::cout<<"size"<<":"<<2*tc.size<<std::endl;
00177                 std::cout<<"coordination_flag"<<":"<< std::hex<<tc.coordination_flag<<std::endl;
00178                 std::cout<<"device_addresss"<<":"<< std::hex<<tc.device_addresss<<std::endl;
00179                 std::cout<<"protocol_version"<<":"<< std::hex<<tc.protocol_version<<std::endl;
00180                 std::cout<<"status"<<":"<<tc.status<<std::endl;
00181                 std::cout<<"scan_number"<<":"<< std::hex<<tc.scan_number<<std::endl;
00182                 std::cout<<"telegram_number"<<":"<< std::hex<<tc.telegram_number<<std::endl;
00183                 std::cout<<"type"<<":"<< std::hex<<tc.type<<std::endl;
00184                 switch(tc.type) {
00185                         case IO: std::cout<<"type"<<": "<<"IO"<<std::endl; break;
00186                         case DISTANCE: std::cout<<"type"<<": "<<"DISTANCE"<<std::endl; break;
00187                         case REFLEXION: std::cout<<"type"<<": "<<"REFLEXION"<<std::endl; break;
00188                         default: std::cout<<"type"<<": "<<"unknown "<<tc.type<<std::endl; break;
00189                 }
00190                 std::cout<<std::dec<<std::endl;
00191         }
00192 
00193         static void print(const TELEGRAM_DISTANCE &tc) {
00194                 std::cout<<"DISTANCE"<<std::endl;
00195                 std::cout<<"type"<<":"<< std::hex<<tc.type<<std::endl;
00196                 switch(tc.type) {
00197                         case _1: std::cout<<"field 1"<<std::endl; break;
00198                         case _2: std::cout<<"field 2"<<std::endl; break;
00199                         case _3: std::cout<<"field 3"<<std::endl; break;
00200                         case _4: std::cout<<"field 4"<<std::endl; break;
00201                         case _5: std::cout<<"field 5"<<std::endl; break;
00202                         default: std::cout<<"unknown "<<tc.type<<std::endl; break;
00203                 }
00204                 std::cout<<std::dec<<std::endl;
00205         }
00206 
00207         static void print(const TELEGRAM_TAIL &tc) {
00208                 std::cout<<"TAIL"<<std::endl;
00209                 std::cout<<"crc"<<":"<< std::hex<<tc.crc<<std::endl;
00210                 std::cout<<std::dec<<std::endl;
00211         }
00212 
00213         //-------------------------------------------
00214         static unsigned int createCRC(uint8_t *ptrData, int Size)
00215         { 
00216                 int CounterWord; 
00217                 unsigned short CrcValue=0xFFFF;
00218 
00219                 for (CounterWord = 0; CounterWord < Size; CounterWord++) 
00220                 { 
00221                         CrcValue = (CrcValue << 8) ^ crc_LookUpTable[ (((uint8_t)(CrcValue >> 8)) ^ *ptrData) ]; 
00222                         ptrData++; 
00223                 } 
00224 
00225                 return (CrcValue); 
00226         }
00227 
00228         //supports versions: 0301, 0201
00229         static bool check(const TELEGRAM_COMMON &tc, const uint8_t DEVICE_ADDR) {
00230                 uint8_t TELEGRAM_COMMON_PATTERN_EQ[] = {0,0,0,0, 0,0, 0,0, 0xFF, DEVICE_ADDR, 2, 1};
00231                 uint8_t TELEGRAM_COMMON_PATTERN_OR[] = {0,0,0,0, 0,0, 0xff,0xff, 0,0, 1, 0};
00232 
00233                 for(size_t i=0; i<sizeof(TELEGRAM_COMMON_PATTERN_EQ); i++) {
00234                         if(TELEGRAM_COMMON_PATTERN_EQ[i] != (tc.bytes[i]&(~TELEGRAM_COMMON_PATTERN_OR[i])) ) {
00235                                 //std::cout<<"invalid at byte "<<i<<std::endl;
00236                                 return false;
00237                         }
00238                 }
00239 
00240                 return true;
00241         }
00242 
00243         TELEGRAM_COMMON tc_;
00244         TELEGRAM_DISTANCE td_;
00245 public:
00246 
00247         bool parseHeader(const unsigned char *buffer, const size_t max_size, const uint8_t DEVICE_ADDR)
00248         {
00249                 if(sizeof(tc_)>max_size) return false;
00250                 tc_ = *((TELEGRAM_COMMON*)buffer);
00251 
00252                 if(!check(tc_, DEVICE_ADDR))
00253                         return false;
00254                 ntoh(tc_);
00255                 //print(tc_);
00256 
00257                 if(tc_.size*2+JUNK_SIZE>(int)max_size) {std::cout<<"inv4"<<std::endl;return false;}
00258 
00259                 TELEGRAM_TAIL tt = *((TELEGRAM_TAIL*) (buffer+(2*tc_.size+JUNK_SIZE-sizeof(TELEGRAM_TAIL))) );
00260                 ntoh(tt);
00261                 //print(tt);
00262 
00263                 if(tt.crc!=createCRC((uint8_t*)buffer+JUNK_SIZE, 2*tc_.size-sizeof(TELEGRAM_TAIL)))
00264                         return false;
00265 
00266                 memset(&td_, 0, sizeof(td_));
00267                 switch(tc_.type) {
00268                         case IO: break;
00269 
00270                         case DISTANCE:
00271                                 td_ = *((TELEGRAM_DISTANCE*)(buffer+sizeof(tc_)));
00272                                 ntoh(td_);
00273                                 //print(td_);
00274                                 break;
00275 
00276                         case REFLEXION: break;
00277                         default: return false;
00278                 }
00279 
00280                 return true;
00281         }
00282 
00283         bool isDist() const {return tc_.type==DISTANCE;}
00284         int getField() const {
00285                 switch(td_.type) {
00286                         case _1: return 0;
00287                         case _2: return 1;
00288                         case _3: return 2;
00289                         case _4: return 3;
00290                         case _5: return 4;
00291                         default: return -1;
00292                 }
00293         }
00294 
00295         void readDistRaw(const unsigned char *buffer, std::vector<int> &res) const
00296         {
00297                 res.clear();
00298                 if(!isDist()) return;
00299 
00300                 size_t num_points = (2*tc_.size - (sizeof(tc_)+sizeof(td_)+sizeof(TELEGRAM_TAIL)-JUNK_SIZE));
00301                 //std::cout<<"num_points: "<<num_points/sizeof(TELEGRAM_S300_DIST_2B)<<std::endl;
00302                 size_t i=0;
00303                 for(; i<num_points; ) {
00304                         TELEGRAM_S300_DIST_2B dist = *((TELEGRAM_S300_DIST_2B*) (buffer+(sizeof(tc_)+sizeof(td_)+i)) );
00305                         res.push_back((int)dist.distance);
00306                         i += sizeof(TELEGRAM_S300_DIST_2B);
00307                 }
00308         }
00309 
00310 };
00311 
00312 
00313 //-----------------------------------------------
00314 ScannerSickS300::ScannerSickS300()
00315 {
00316         m_Param.iDataLength = 1104;
00317         m_Param.iHeaderLength = 24;
00318         // scanner has a half degree resolution and a VoW of 270 degrees
00319         m_Param.iNumScanPoints = 541;
00320         m_Param.dScale = 0.01;
00321         m_Param.dStartAngle = -135.0/180.0*c_dPi;
00322         m_Param.dStopAngle = 135.0/180.0*c_dPi;
00323 
00324         // allows to set different Baud-Multipliers depending on used SerialIO-Card
00325         m_dBaudMult = 1.0;
00326 
00327         // init scan with zeros
00328         m_viScanRaw.assign(541, 0);
00329         m_iPosReadBuf2 = 0;
00330         
00331         m_actualBufferSize = 0;
00332 
00333 }
00334 
00335 
00336 //-------------------------------------------
00337 ScannerSickS300::~ScannerSickS300()
00338 {
00339         m_SerialIO.closeIO();
00340 }
00341 
00342 
00343 // ---------------------------------------------------------------------------
00344 bool ScannerSickS300::open(const char* pcPort, int iBaudRate, int iScanId=7)
00345 {
00346     int bRetSerial;
00347 
00348         // update scan id (id=8 for slave scanner, else 7)
00349         m_iScanId = iScanId;
00350         
00351         // initialize Serial Interface
00352         m_SerialIO.setBaudRate(iBaudRate);
00353         m_SerialIO.setDeviceName(pcPort);
00354         m_SerialIO.setBufferSize(READ_BUF_SIZE - 10 , WRITE_BUF_SIZE -10 );
00355         m_SerialIO.setHandshake(SerialIO::HS_NONE);
00356         m_SerialIO.setMultiplier(m_dBaudMult);
00357         bRetSerial = m_SerialIO.openIO();
00358         m_SerialIO.setTimeout(0.0);
00359         m_SerialIO.SetFormat(8, SerialIO::PA_NONE, SerialIO::SB_ONE);
00360 
00361     if(bRetSerial == 0)
00362     {
00363             // Clears the read and transmit buffer.
00364             m_iPosReadBuf2 = 0;
00365             m_SerialIO.purge();
00366             return true;
00367     }
00368     else
00369     {
00370         return false;
00371     }
00372 }
00373 
00374 
00375 //-------------------------------------------
00376 void ScannerSickS300::purgeScanBuf()
00377 {
00378         m_iPosReadBuf2 = 0;
00379         m_SerialIO.purge();
00380 }
00381 
00382 
00383 //-------------------------------------------
00384 void ScannerSickS300::resetStartup()
00385 {
00386 }
00387 
00388 
00389 //-------------------------------------------
00390 void ScannerSickS300::startScanner()
00391 {
00392 }
00393 
00394 
00395 //-------------------------------------------
00396 void ScannerSickS300::stopScanner()
00397 {
00398 }
00399 
00400 
00401 //-----------------------------------------------
00402 bool ScannerSickS300::getScan(std::vector<double> &vdDistanceM, std::vector<double> &vdAngleRAD, std::vector<double> &vdIntensityAU, unsigned int &iTimestamp, unsigned int &iTimeNow)
00403 {
00404         bool bRet = false;
00405         int i;
00406         int iNumRead = 0;
00407         int iNumRead2 = 0;
00408         std::vector<ScanPolarType> vecScanPolar;
00409         vecScanPolar.resize(m_Param.iNumScanPoints);
00410 
00411         iNumRead2 = m_SerialIO.readNonBlocking((char*)m_ReadBuf+m_actualBufferSize, SCANNER_S300_READ_BUF_SIZE-2-m_actualBufferSize);
00412 
00413         iNumRead = m_actualBufferSize + iNumRead2;
00414         m_actualBufferSize = m_actualBufferSize + iNumRead2;
00415 
00416         if( iNumRead < m_Param.iDataLength )
00417         {
00418                 // not enough data in queue --> abort reading
00419           //    printf("Not enough data in queue, read data at slower rate!\n");
00420                 return false;
00421         }
00422         
00423         TelegramParser tp;
00424 
00425         // Try to find scan. Searching backwards in the receive queue.
00426         for(i=iNumRead; i>=0; i--)
00427         {
00428                 // parse through the telegram until header with correct scan id is found
00429                 if(tp.parseHeader(m_ReadBuf+i, iNumRead-i, m_iScanId))
00430                 {
00431                         tp.readDistRaw(m_ReadBuf+i, m_viScanRaw);
00432                         if(m_viScanRaw.size()>0) {
00433                                 // Scan was succesfully read from buffer
00434                                 bRet = true;
00435                                 m_actualBufferSize = 0;
00436                                 break;
00437                         }
00438                 }
00439         }
00440         
00441         if(bRet)
00442         {
00443                 // convert data into range and intensity information
00444                 convertScanToPolar(m_viScanRaw, vecScanPolar);
00445 
00446                 // resize vectors to size of Scan
00447                 vdDistanceM.resize(vecScanPolar.size());
00448                 vdAngleRAD.resize(vecScanPolar.size());
00449                 vdIntensityAU.resize(vecScanPolar.size());
00450                 // assign outputs
00451                 for(unsigned int i=0; i < vecScanPolar.size(); i++)
00452                 {
00453                         vdDistanceM[i] = vecScanPolar[i].dr;
00454                         vdAngleRAD[i] = vecScanPolar[i].da;
00455                         vdIntensityAU[i] = vecScanPolar[i].di;
00456                 }       
00457         }
00458 
00459         return bRet;
00460 }
00461 
00462 //-------------------------------------------
00463 void ScannerSickS300::convertScanToPolar(std::vector<int> viScanRaw,
00464                                                         std::vector<ScanPolarType>& vecScanPolar )
00465 {       
00466         double dDist;
00467         double dAngle, dAngleStep;
00468         double dIntens;
00469 
00470         dAngleStep = fabs(m_Param.dStopAngle - m_Param.dStartAngle) / double(m_Param.iNumScanPoints - 1) ;
00471         
00472         for(int i=0; i<m_Param.iNumScanPoints; i++)
00473         {
00474                 dDist = double ((viScanRaw[i] & 0x1FFF) * m_Param.dScale);
00475 
00476                 dAngle = m_Param.dStartAngle + i*dAngleStep;
00477                 dIntens = double(viScanRaw[i] & 0x2000);
00478 
00479                 vecScanPolar[i].dr = dDist;
00480                 vecScanPolar[i].da = dAngle;
00481                 vecScanPolar[i].di = dIntens;
00482         }
00483 }


cob_sick_s300
Author(s): Florian Weisshardt
autogenerated on Sun Oct 5 2014 23:05:19