00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054 #include <cob_sick_s300/ScannerSickS300.h>
00055
00056
00057
00058 typedef unsigned char BYTE;
00059
00060 const double ScannerSickS300::c_dPi = 3.14159265358979323846;
00061
00062 const unsigned char ScannerSickS300::c_StartBytes[10] = {0,0,0,0,0,0,0,0,255,7};
00063
00064 unsigned char ScannerSickS300::m_iScanId = 7;
00065
00066 const unsigned short ScannerSickS300::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
00103 ScannerSickS300::ScannerSickS300()
00104 {
00105 m_Param.iDataLength = 1104;
00106 m_Param.iHeaderLength = 24;
00107
00108 m_Param.iNumScanPoints = 541;
00109 m_Param.dScale = 0.01;
00110 m_Param.dStartAngle = -135.0/180.0*c_dPi;
00111 m_Param.dStopAngle = 135.0/180.0*c_dPi;
00112
00113
00114 m_dBaudMult = 1.0;
00115
00116
00117 m_viScanRaw.assign(541, 0);
00118 m_iPosReadBuf2 = 0;
00119
00120 }
00121
00122
00123
00124 ScannerSickS300::~ScannerSickS300()
00125 {
00126 m_SerialIO.close();
00127 }
00128
00129
00130
00131 bool ScannerSickS300::open(const char* pcPort, int iBaudRate, int iScanId=7)
00132 {
00133 int bRetSerial;
00134
00135
00136 if (iBaudRate != 500000)
00137 return false;
00138
00139
00140 m_iScanId = iScanId;
00141
00142
00143 m_SerialIO.setBaudRate(iBaudRate);
00144 m_SerialIO.setDeviceName(pcPort);
00145 m_SerialIO.setBufferSize(READ_BUF_SIZE - 10 , WRITE_BUF_SIZE -10 );
00146 m_SerialIO.setHandshake(SerialIO::HS_NONE);
00147 m_SerialIO.setMultiplier(m_dBaudMult);
00148 bRetSerial = m_SerialIO.open();
00149 m_SerialIO.setTimeout(0.0);
00150 m_SerialIO.SetFormat(8, SerialIO::PA_NONE, SerialIO::SB_ONE);
00151
00152 if(bRetSerial == 0)
00153 {
00154
00155 m_iPosReadBuf2 = 0;
00156 m_SerialIO.purge();
00157 return true;
00158 }
00159 else
00160 {
00161 return false;
00162 }
00163 }
00164
00165
00166
00167 void ScannerSickS300::purgeScanBuf()
00168 {
00169 m_iPosReadBuf2 = 0;
00170 m_SerialIO.purge();
00171 }
00172
00173
00174
00175 void ScannerSickS300::resetStartup()
00176 {
00177 }
00178
00179
00180
00181 void ScannerSickS300::startScanner()
00182 {
00183 }
00184
00185
00186
00187 void ScannerSickS300::stopScanner()
00188 {
00189 }
00190
00191
00192
00193 bool ScannerSickS300::getScan(std::vector<double> &vdDistanceM, std::vector<double> &vdAngleRAD, std::vector<double> &vdIntensityAU, unsigned int &iTimestamp, unsigned int &iTimeNow)
00194 {
00195 bool bRet = false;
00196 int i,j;
00197 int iNumRead;
00198 int iNumData;
00199 int iFirstByteOfHeader;
00200 int iFirstByteOfData;
00201 unsigned int iTelegramNumber;
00202 unsigned int uiReadCRC;
00203 unsigned int uiCalcCRC;
00204 std::vector<ScanPolarType> vecScanPolar;
00205 vecScanPolar.resize(m_Param.iNumScanPoints);
00206
00207 iNumRead = m_SerialIO.readNonBlocking((char*)m_ReadBuf, SCANNER_S300_READ_BUF_SIZE-2);
00208
00209 if( iNumRead < m_Param.iDataLength )
00210 {
00211
00212 printf("Not enough data in queue, read data at slower rate!\n");
00213 return false;
00214 }
00215
00216
00217 for(i=iNumRead-m_Param.iDataLength; i>=0; i--)
00218 {
00219
00220 if (
00221 ( m_ReadBuf[i+0] == c_StartBytes[0] ) &&
00222 ( m_ReadBuf[i+1] == c_StartBytes[1] ) &&
00223 ( m_ReadBuf[i+2] == c_StartBytes[2] ) &&
00224 ( m_ReadBuf[i+3] == c_StartBytes[3] ) &&
00225 ( m_ReadBuf[i+4] == c_StartBytes[4] ) &&
00226 ( m_ReadBuf[i+5] == c_StartBytes[5] ) &&
00227 ( m_ReadBuf[i+8] == c_StartBytes[8] ) &&
00228 ( m_ReadBuf[i+9] == m_iScanId )
00229 )
00230
00231 {
00232
00233 iFirstByteOfHeader = i;
00234
00235
00236 iTimestamp = (m_ReadBuf[i+17]<<24) | (m_ReadBuf[i+16]<<16) | (m_ReadBuf[i+15]<<8) | (m_ReadBuf[i+14]);
00237 iTelegramNumber = (m_ReadBuf[i+19]<<8) | (m_ReadBuf[i+18]);
00238
00239 if(iNumRead-iFirstByteOfHeader > m_Param.iDataLength+4+17) {
00240
00241
00242
00243
00244 iTimeNow = (m_ReadBuf[i+m_Param.iDataLength+4+17]<<24) | (m_ReadBuf[i+m_Param.iDataLength+4+16]<<16) | (m_ReadBuf[i+m_Param.iDataLength+4+15]<<8) | (m_ReadBuf[i+m_Param.iDataLength+4+14]);
00245 } else iTimeNow = 0;
00246
00247 iFirstByteOfData = i + m_Param.iHeaderLength;
00248
00249
00250
00251 iNumData = 2 * getUnsignedWord(m_ReadBuf[iFirstByteOfHeader + 6],
00252 m_ReadBuf[iFirstByteOfHeader + 7]);
00253
00254 if ( iNumData != m_Param.iDataLength ) {
00255 continue;
00256 }
00257
00258
00259
00260
00261
00262 uiReadCRC = getUnsignedWord(m_ReadBuf[iFirstByteOfHeader + 4 + iNumData - 1],
00263 m_ReadBuf[iFirstByteOfHeader + 4 + iNumData - 2]);
00264
00265 uiCalcCRC = createCRC(&m_ReadBuf[iFirstByteOfHeader + 4], m_Param.iDataLength - 2);
00266
00267
00268 if (uiReadCRC == uiCalcCRC)
00269 {
00270 for(j=0; j<m_Param.iNumScanPoints; j++)
00271 {
00272
00273 m_viScanRaw[j] = getUnsignedWord(m_ReadBuf[iFirstByteOfData + 2 * j + 1],
00274 m_ReadBuf[iFirstByteOfData + 2 * j ]);
00275 }
00276
00277 bRet = true;
00278 break;
00279 }
00280 }
00281 }
00282
00283 if(bRet)
00284 {
00285
00286 convertScanToPolar(m_viScanRaw, vecScanPolar);
00287
00288
00289 vdDistanceM.resize(vecScanPolar.size());
00290 vdAngleRAD.resize(vecScanPolar.size());
00291 vdIntensityAU.resize(vecScanPolar.size());
00292
00293 for(unsigned int i=0; i < vecScanPolar.size(); i++)
00294 {
00295 vdDistanceM[i] = vecScanPolar[i].dr;
00296 vdAngleRAD[i] = vecScanPolar[i].da;
00297 vdIntensityAU[i] = vecScanPolar[i].di;
00298 }
00299 }
00300
00301 return bRet;
00302 }
00303
00304
00305
00306 unsigned int ScannerSickS300::createCRC(unsigned char *ptrData, int Size)
00307 {
00308 int CounterWord;
00309 unsigned short CrcValue=0xFFFF;
00310
00311 for (CounterWord = 0; CounterWord < Size; CounterWord++)
00312 {
00313 CrcValue = (CrcValue << 8) ^ crc_LookUpTable[ (((BYTE)(CrcValue >> 8)) ^ *ptrData) ];
00314 ptrData++;
00315 }
00316
00317 return (CrcValue);
00318 }
00319
00320
00321
00322 void ScannerSickS300::convertScanToPolar(std::vector<int> viScanRaw,
00323 std::vector<ScanPolarType>& vecScanPolar )
00324 {
00325 double dDist;
00326 double dAngle, dAngleStep;
00327 double dIntens;
00328
00329 dAngleStep = fabs(m_Param.dStopAngle - m_Param.dStartAngle) / double(m_Param.iNumScanPoints - 1) ;
00330
00331 for(int i=0; i<m_Param.iNumScanPoints; i++)
00332 {
00333 dDist = double ((viScanRaw[i] & 0x1FFF) * m_Param.dScale);
00334
00335 dAngle = m_Param.dStartAngle + i*dAngleStep;
00336 dIntens = double(viScanRaw[i] & 0x2000);
00337
00338 vecScanPolar[i].dr = dDist;
00339 vecScanPolar[i].da = dAngle;
00340 vecScanPolar[i].di = dIntens;
00341 }
00342 }