sick_generic_parser.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013, Osnabrück University
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Osnabrück University nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: 14.11.2013
30  *
31  * Author: Martin Günther <mguenthe@uos.de>
32  *
33  */
34 
35 #ifndef SICK_GENERIC_PARSER_H_
36 #define SICK_GENERIC_PARSER_H_
37 
38 // List of supported laser scanner and radar scanner
39 #define SICK_SCANNER_LMS_1XXX_NAME "sick_lms_1xxx"
40 #define SICK_SCANNER_MRS_1XXX_NAME "sick_mrs_1xxx"
41 #define SICK_SCANNER_TIM_5XX_NAME "sick_tim_5xx"
42 #define SICK_SCANNER_TIM_7XX_NAME "sick_tim_7xx"
43 #define SICK_SCANNER_LMS_5XX_NAME "sick_lms_5xx"
44 #define SICK_SCANNER_LMS_1XX_NAME "sick_lms_1xx"
45 #define SICK_SCANNER_MRS_6XXX_NAME "sick_mrs_6xxx"
46 #define SICK_SCANNER_RMS_3XX_NAME "sick_rms_3xx"
47 #include "abstract_parser.h"
48 
49 #include "sensor_msgs/LaserScan.h"
51 #include "sick_scan/dataDumper.h"
52 // namespace sensor_msgs
53 namespace sick_scan
54 {
56  {
57  public:
58  void setScannerName(std::string _s);
59  std::string getScannerName(void);
60  void setNumberOfLayers(int _layerNum);
61  int getNumberOfLayers(void);
62  void setNumberOfShots(int _shots);
63  int getNumberOfShots(void);
64  void setNumberOfMaximumEchos(int _maxEchos);
65  int getNumberOfMaximumEchos(void);
66  void setAngularDegreeResolution(double _res);
67  void setElevationDegreeResolution(double _elevRes);
68  double getElevationDegreeResolution(void);
69  double getAngularDegreeResolution(void);
70  double getExpectedFrequency(void);
71  bool getDeviceIsRadar(void);
72  bool getUseBinaryProtocol(void);
73  void setUseBinaryProtocol(bool _useBinary);
74  void setDeviceIsRadar(bool _deviceIsRadar);
75  void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit);
77  void setExpectedFrequency(double _freq);
79  private:
80  std::string scannerName;
90 
92  };
93 
94 
95 
97  {
98  public:
99  SickGenericParser(std::string scannerType);
100  virtual ~SickGenericParser();
101 
102  virtual int parse_datagram(char* datagram, size_t datagram_length, SickScanConfig &config,
103  sensor_msgs::LaserScan &msg, int &numEchos, int& echoMask);
104 
105 
106  void checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol);
107 
108  void set_range_min(float min);
109  void set_range_max(float max);
110 
111  float get_range_min(void);
112  float get_range_max(void);
113 
114  void set_time_increment(float time);
115  void setScannerType(std::string s);
116  std::string getScannerType(void);
117  int lookUpForAllowedScanner(std::string scannerName);
118  void setCurrentParamPtr(ScannerBasicParam* _ptr);
119  ScannerBasicParam *getCurrentParamPtr();
120 
121 
122  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);
123 
124 
125  private:
126  float override_range_min_, override_range_max_;
128  std::string scannerType;
129  std::vector<std::string> allowedScannerNames;
130  std::vector<ScannerBasicParam> basicParams;
132  };
133 
134 } /* namespace sick_scan */
135 #endif /* SICK_GENERIC_PARSER_H_ */
msg
void setNumberOfMaximumEchos(int _maxEchos)
Set number of maximum echoes for this laser scanner type.
double getElevationDegreeResolution(void)
get angular resolution in VERTICAL direction for multilayer scanner
void setNumberOfLayers(int _layerNum)
Setting number of scanner layers (depending of scanner type/family)
double getExpectedFrequency(void)
get expected scan frequency
void setElevationDegreeResolution(double _elevRes)
set angular resolution in VERTICAL direction for multilayer scanner
ScannerBasicParam * currentParamSet
void setDeviceIsRadar(bool _deviceIsRadar)
flag to mark the device as radar (instead of laser scanner)
int getNumberOfShots(void)
Get number of shots per scan.
bool getIntensityResolutionIs16Bit(void)
Get the RSSI Value length.
void setNumberOfShots(int _shots)
Set number of shots per scan.
void setAngularDegreeResolution(double _res)
Set angular resolution in degrees.
int getNumberOfLayers(void)
Getting number of scanner layers.
int getNumberOfMaximumEchos(void)
Get number of maximum echoes for this laser scanner type.
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
double getAngularDegreeResolution(void)
Get angular resolution in degress.
void setScannerName(std::string _s)
Setting name (type) of scanner.
std::string getScannerName(void)
Getting name (type) of scanner.
std::vector< std::string > allowedScannerNames
ScannerBasicParam()
Construction of parameter object.
int min(int a, int b)
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
std::vector< ScannerBasicParam > basicParams
void setUseBinaryProtocol(bool _useBinary)
flag to decide between usage of ASCII-sopas or BINARY-sopas
void setExpectedFrequency(double _freq)
set expected scan frequency
static sick_scan::SickScanCommonTcp * s
bool getDeviceIsRadar(void)
flag to mark the device as radar (instead of laser scanner)


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Tue Jul 9 2019 04:55:32