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