Go to the documentation of this file.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 #ifndef SICK_GENERIC_PARSER_H_
00036 #define SICK_GENERIC_PARSER_H_
00037
00038
00039 #define SICK_SCANNER_LMS_1XXX_NAME "sick_lms_1xxx"
00040 #define SICK_SCANNER_MRS_1XXX_NAME "sick_mrs_1xxx"
00041 #define SICK_SCANNER_TIM_5XX_NAME "sick_tim_5xx"
00042 #define SICK_SCANNER_TIM_7XX_NAME "sick_tim_7xx"
00043 #define SICK_SCANNER_LMS_5XX_NAME "sick_lms_5xx"
00044 #define SICK_SCANNER_LMS_1XX_NAME "sick_lms_1xx"
00045 #define SICK_SCANNER_MRS_6XXX_NAME "sick_mrs_6xxx"
00046 #define SICK_SCANNER_RMS_3XX_NAME "sick_rms_3xx"
00047 #include "abstract_parser.h"
00048
00049 #include "sensor_msgs/LaserScan.h"
00050 #include "sick_scan/sick_scan_common.h"
00051 #include "sick_scan/dataDumper.h"
00052
00053 namespace sick_scan
00054 {
00055 class ScannerBasicParam
00056 {
00057 public:
00058 void setScannerName(std::string _s);
00059 std::string getScannerName(void);
00060 void setNumberOfLayers(int _layerNum);
00061 int getNumberOfLayers(void);
00062 void setNumberOfShots(int _shots);
00063 int getNumberOfShots(void);
00064 void setNumberOfMaximumEchos(int _maxEchos);
00065 int getNumberOfMaximumEchos(void);
00066 void setAngularDegreeResolution(double _res);
00067 void setElevationDegreeResolution(double _elevRes);
00068 double getElevationDegreeResolution(void);
00069 double getAngularDegreeResolution(void);
00070 double getExpectedFrequency(void);
00071 bool getDeviceIsRadar(void);
00072 bool getUseBinaryProtocol(void);
00073 void setUseBinaryProtocol(bool _useBinary);
00074 void setDeviceIsRadar(bool _deviceIsRadar);
00075 void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit);
00076 bool getIntensityResolutionIs16Bit(void);
00077 void setExpectedFrequency(double _freq);
00078 ScannerBasicParam();
00079 private:
00080 std::string scannerName;
00081 int numberOfLayers;
00082 int numberOfShots;
00083 int numberOfMaximumEchos;
00084 double elevationDegreeResolution;
00085 double angleDegressResolution;
00086 double expectedFrequency;
00087 bool useBinaryProtocol;
00088 bool IntensityResolutionIs16Bit;
00089 bool deviceIsRadar;
00090
00091 bool CartographerCompatibility;
00092 };
00093
00094
00095
00096 class SickGenericParser : public AbstractParser
00097 {
00098 public:
00099 SickGenericParser(std::string scannerType);
00100 virtual ~SickGenericParser();
00101
00102 virtual int parse_datagram(char* datagram, size_t datagram_length, SickScanConfig &config,
00103 sensor_msgs::LaserScan &msg, int &numEchos, int& echoMask);
00104
00105
00106 void checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol);
00107
00108 void set_range_min(float min);
00109 void set_range_max(float max);
00110
00111 float get_range_min(void);
00112 float get_range_max(void);
00113
00114 void set_time_increment(float time);
00115 void setScannerType(std::string s);
00116 std::string getScannerType(void);
00117 int lookUpForAllowedScanner(std::string scannerName);
00118 void setCurrentParamPtr(ScannerBasicParam* _ptr);
00119 ScannerBasicParam *getCurrentParamPtr();
00120
00121
00122 int checkForDistAndRSSI(std::vector<char *>& fields, int expected_number_of_data, int& distNum, int& rssiNum, std::vector<float>& distVal, std::vector<float>& rssiVal,int& distMask);
00123
00124
00125 private:
00126 float override_range_min_, override_range_max_;
00127 float override_time_increment_;
00128 std::string scannerType;
00129 std::vector<std::string> allowedScannerNames;
00130 std::vector<ScannerBasicParam> basicParams;
00131 ScannerBasicParam *currentParamSet;
00132 };
00133
00134 }
00135 #endif