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 #include <stdint.h>
00057
00058
00059
00060 typedef unsigned char BYTE;
00061
00062 const double ScannerSickS300::c_dPi = 3.14159265358979323846;
00063 unsigned char ScannerSickS300::m_iScanId = 7;
00064
00065 const unsigned short crc_LookUpTable[256]
00066 = {
00067 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
00068 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
00069 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
00070 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
00071 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485,
00072 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
00073 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4,
00074 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
00075 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
00076 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
00077 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12,
00078 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
00079 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41,
00080 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
00081 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70,
00082 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
00083 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F,
00084 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
00085 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E,
00086 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
00087 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D,
00088 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
00089 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C,
00090 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
00091 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB,
00092 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
00093 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
00094 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
00095 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9,
00096 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
00097 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
00098 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
00099 };
00100
00101 unsigned int TelegramParser::createCRC(uint8_t *ptrData, int Size)
00102 {
00103 int CounterWord;
00104 unsigned short CrcValue=0xFFFF;
00105
00106 for (CounterWord = 0; CounterWord < Size; CounterWord++)
00107 {
00108 CrcValue = (CrcValue << 8) ^ crc_LookUpTable[ (((uint8_t)(CrcValue >> 8)) ^ *ptrData) ];
00109 ptrData++;
00110 }
00111
00112 return (CrcValue);
00113 }
00114
00115
00116 ScannerSickS300::ScannerSickS300()
00117 {
00118
00119 m_dBaudMult = 1.0;
00120
00121
00122 m_iPosReadBuf2 = 0;
00123
00124 m_actualBufferSize = 0;
00125
00126 m_bInStandby = true;
00127
00128 }
00129
00130
00131
00132 ScannerSickS300::~ScannerSickS300()
00133 {
00134 m_SerialIO.closeIO();
00135 }
00136
00137
00138
00139 bool ScannerSickS300::open(const char* pcPort, int iBaudRate, int iScanId=7)
00140 {
00141 int bRetSerial;
00142
00143
00144 m_iScanId = iScanId;
00145
00146
00147 m_SerialIO.setBaudRate(iBaudRate);
00148 m_SerialIO.setDeviceName(pcPort);
00149 m_SerialIO.setBufferSize(READ_BUF_SIZE - 10 , WRITE_BUF_SIZE -10 );
00150 m_SerialIO.setHandshake(SerialIO::HS_NONE);
00151 m_SerialIO.setMultiplier(m_dBaudMult);
00152 bRetSerial = m_SerialIO.openIO();
00153 m_SerialIO.setTimeout(0.0);
00154 m_SerialIO.SetFormat(8, SerialIO::PA_NONE, SerialIO::SB_ONE);
00155
00156 if(bRetSerial == 0)
00157 {
00158
00159 m_iPosReadBuf2 = 0;
00160 m_SerialIO.purge();
00161 return true;
00162 }
00163 else
00164 {
00165 return false;
00166 }
00167 }
00168
00169
00170
00171 void ScannerSickS300::purgeScanBuf()
00172 {
00173 m_iPosReadBuf2 = 0;
00174 m_SerialIO.purge();
00175 }
00176
00177
00178
00179 void ScannerSickS300::resetStartup()
00180 {
00181 }
00182
00183
00184
00185 void ScannerSickS300::startScanner()
00186 {
00187 }
00188
00189
00190
00191 void ScannerSickS300::stopScanner()
00192 {
00193 }
00194
00195
00196 bool ScannerSickS300::getScan(std::vector<double> &vdDistanceM, std::vector<double> &vdAngleRAD, std::vector<double> &vdIntensityAU, unsigned int &iTimestamp, unsigned int &iTimeNow, const bool debug)
00197 {
00198 bool bRet = false;
00199 int i;
00200 int iNumRead2 = 0;
00201 std::vector<ScanPolarType> vecScanPolar;
00202
00203 iTimeNow=0;
00204
00205 if(SCANNER_S300_READ_BUF_SIZE-2-m_actualBufferSize<=0)
00206 m_actualBufferSize=0;
00207
00208 iNumRead2 = m_SerialIO.readBlocking((char*)m_ReadBuf+m_actualBufferSize, SCANNER_S300_READ_BUF_SIZE-2-m_actualBufferSize);
00209 if(iNumRead2<=0) return false;
00210
00211 m_actualBufferSize = m_actualBufferSize + iNumRead2;
00212
00213
00214 for(i=m_actualBufferSize; i>=0; i--)
00215 {
00216
00217 if(tp_.parseHeader(m_ReadBuf+i, m_actualBufferSize-i, m_iScanId, debug))
00218 {
00219 tp_.readDistRaw(m_ReadBuf+i, m_viScanRaw);
00220 if(m_viScanRaw.size()>0) {
00221
00222 bRet = true;
00223 int old = m_actualBufferSize;
00224 m_actualBufferSize -= tp_.getCompletePacketSize()+i;
00225 for(int i=0; i<old-m_actualBufferSize; i++)
00226 m_ReadBuf[i] = m_ReadBuf[i+old-m_actualBufferSize];
00227 break;
00228 }
00229 }
00230 }
00231
00232 PARAM_MAP::const_iterator param = m_Params.find(tp_.getField());
00233 if(bRet && param!=m_Params.end())
00234 {
00235
00236 convertScanToPolar(param, m_viScanRaw, vecScanPolar);
00237
00238
00239 vdDistanceM.resize(vecScanPolar.size());
00240 vdAngleRAD.resize(vecScanPolar.size());
00241 vdIntensityAU.resize(vecScanPolar.size());
00242
00243 for(unsigned int i=0; i < vecScanPolar.size(); i++)
00244 {
00245 vdDistanceM[i] = vecScanPolar[i].dr;
00246 vdAngleRAD[i] = vecScanPolar[i].da;
00247 vdIntensityAU[i] = vecScanPolar[i].di;
00248 }
00249 }
00250
00251 return bRet;
00252 }
00253
00254
00255 void ScannerSickS300::convertScanToPolar(const PARAM_MAP::const_iterator param, std::vector<int> viScanRaw,
00256 std::vector<ScanPolarType>& vecScanPolar )
00257 {
00258 double dDist;
00259 double dAngle, dAngleStep;
00260 double dIntens;
00261 bool bInStandby = true;
00262
00263 vecScanPolar.resize(viScanRaw.size());
00264 dAngleStep = fabs(param->second.dStopAngle - param->second.dStartAngle) / double(viScanRaw.size() - 1) ;
00265
00266
00267 for(size_t i=0; i<viScanRaw.size(); i++)
00268 {
00269 dDist = double ((viScanRaw[i] & 0x1FFF) * param->second.dScale);
00270
00271
00272 if ( !(viScanRaw[i] == 0x4004) )
00273 bInStandby = false;
00274
00275 dAngle = param->second.dStartAngle + i*dAngleStep;
00276 dIntens = double(viScanRaw[i] & 0x2000);
00277
00278 vecScanPolar[i].dr = dDist;
00279 vecScanPolar[i].da = dAngle;
00280 vecScanPolar[i].di = dIntens;
00281 }
00282
00283 m_bInStandby = bInStandby;
00284 }