ScannerSickS300.h
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 #ifndef SCANNERSICKS300_INCLUDEDEF_H
00055 #define SCANNERSICKS300_INCLUDEDEF_H
00056 //-----------------------------------------------
00057 
00058 // base classes
00059 #include <string>
00060 #include <vector>
00061 #include <iostream>
00062 #include <math.h>
00063 #include <stdio.h>
00064 
00065 #include <cob_sick_s300/SerialIO.h>
00066 
00102 class ScannerSickS300
00103 {
00104 public:
00105 
00106         // set of parameters which are specific to the SickS300
00107         struct ParamType
00108         {
00109                 int iDataLength;        // length of data telegram
00110                 int iHeaderLength;      // length of telegram header
00111                 int iNumScanPoints;     // number of measurements in the scan
00112                 double dScale;          // scaling of the scan (multiply with to get scan in meters)
00113                 double dStartAngle;     // scan start angle
00114                 double dStopAngle;      // scan stop angle
00115         };
00116 
00117         // storage container for received scanner data
00118         struct ScanPolarType
00119         {
00120                 double dr; // distance //r;
00121                 double da; // angle //a;
00122                 double di; // intensity; //bool bGlare;
00123         };
00124 
00125         enum
00126         {
00127                 SCANNER_S300_READ_BUF_SIZE = 10000,
00128                 READ_BUF_SIZE = 10000,
00129                 WRITE_BUF_SIZE = 10000
00130         };
00131 
00132         // Constructor
00133         ScannerSickS300();
00134 
00135         // Destructor
00136         ~ScannerSickS300();
00137 
00144         bool open(const char* pcPort, int iBaudRate, int iScanId);
00145         //bool open(char* pcPort, int iBaudRate);
00146 
00147         // not implemented
00148         void resetStartup();
00149 
00150         // not implmented
00151         void startScanner();
00152 
00153         // not implemented
00154         void stopScanner();
00155         //sick_lms.Uninitialize();
00156 
00157         void purgeScanBuf();
00158 
00159         bool getScan(std::vector<double> &vdDistanceM, std::vector<double> &vdAngleRAD, std::vector<double> &vdIntensityAU, unsigned int &iTimestamp, unsigned int &iTimeNow);
00160         //sick_lms.GetSickScan(values, num_values);
00161 
00162         // add sick_lms.GetSickScanResolution();
00163 
00164         // add sick_lms.GetSickMeasuringUnits();
00165 
00166 
00167 private:
00168 
00169         // Constants
00170         static const unsigned short crc_LookUpTable[256];
00171         static const unsigned char c_StartBytes[10];
00172         static const double c_dPi;
00173 
00174         // Parameters
00175         ParamType m_Param;
00176         double m_dBaudMult;
00177 
00178         // Variables
00179         unsigned char m_ReadBuf[READ_BUF_SIZE+10];
00180         unsigned char m_ReadBuf2[READ_BUF_SIZE+10];
00181         unsigned int m_uiSumReadBytes;
00182         std::vector<int> m_viScanRaw;
00183         int m_iPosReadBuf2;
00184         static unsigned char m_iScanId;
00185 
00186         // Components
00187         SerialIO m_SerialIO;
00188 
00189         // Functions
00190         unsigned int getUnsignedWord(unsigned char msb, unsigned char lsb)
00191         {
00192                 return (msb << 8) | lsb;
00193         }
00194 
00195         unsigned int createCRC(unsigned char *ptrData, int Size);
00196 
00197         void convertScanToPolar(std::vector<int> viScanRaw,
00198                                                         std::vector<ScanPolarType>& vecScanPolar);
00199 
00200 };
00201 
00202 //-----------------------------------------------
00203 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


cob_sick_s300
Author(s): Florian Weisshardt
autogenerated on Fri Mar 1 2013 17:47:50