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_240_NAME "sick_tim_240"
42 #define SICK_SCANNER_TIM_5XX_NAME "sick_tim_5xx"
43 #define SICK_SCANNER_TIM_7XX_NAME "sick_tim_7xx"
44 #define SICK_SCANNER_TIM_7XXS_NAME "sick_tim_7xxS"
45 #define SICK_SCANNER_LMS_5XX_NAME "sick_lms_5xx"
46 #define SICK_SCANNER_LMS_1XX_NAME "sick_lms_1xx"
47 #define SICK_SCANNER_MRS_6XXX_NAME "sick_mrs_6xxx"
48 #define SICK_SCANNER_LMS_4XXX_NAME "sick_lms_4xxx"
49 #define SICK_SCANNER_RMS_3XX_NAME "sick_rms_3xx"
50 #define SICK_SCANNER_NAV_3XX_NAME "sick_nav_3xx"
51 #define SICK_SCANNER_NAV_2XX_NAME "sick_nav_2xx"
52 #define SICK_SCANNER_TIM_4XX_NAME "sick_tim_4xx"
53 #include "abstract_parser.h"
54 
55 #include "sensor_msgs/LaserScan.h"
57 #include "sick_scan/dataDumper.h"
58 // namespace sensor_msgs
59 namespace sick_scan
60 {
61  enum EVAL_FIELD_SUPPORT // type of eval field support:
62  {
63  EVAL_FIELD_UNSUPPORTED = 0, // Lidar does not support eval field (default)
64  USE_EVAL_FIELD_TIM7XX_LOGIC, // eval fields supported by TiM7xx and TiM7xxS
65  USE_EVAL_FIELD_LMS5XX_LOGIC, // eval fields supported by LMS5XX
66  USE_EVAL_FIELD_LMS5XX_UNSUPPORTED, // eval fields not supported by LMS5XX
67  USE_EVAL_FIELD_NUM // max number of eval field support types
68  };
69 
71  {
72  public:
73  void setScannerName(std::string _s);
74 
75  std::string getScannerName(void);
76 
77  void setNumberOfLayers(int _layerNum);
78 
79  int getNumberOfLayers(void);
80 
81  void setNumberOfShots(int _shots);
82 
83  int getNumberOfShots(void);
84 
85  void setNumberOfMaximumEchos(int _maxEchos);
86 
87  int getNumberOfMaximumEchos(void);
88 
89  void setAngularDegreeResolution(double _res);
90 
91  void setElevationDegreeResolution(double _elevRes);
92 
93  double getElevationDegreeResolution(void);
94 
95  double getAngularDegreeResolution(void);
96 
97  double getExpectedFrequency(void);
98 
99  bool getDeviceIsRadar(void);
100 
101  bool getUseBinaryProtocol(void);
102 
103  void setScanMirroredAndShifted(bool _scanMirroredAndShifted);
104 
106 
107  void setUseBinaryProtocol(bool _useBinary);
108 
109  void setDeviceIsRadar(bool _deviceIsRadar);
110 
111  void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit);
112 
114 
115  void setExpectedFrequency(double _freq);
116 
118 
119  void setUseSafetyPasWD(bool _useSafetyPasWD);
120 
121  bool getUseSafetyPasWD();
122 
123  void setEncoderMode(int8_t _EncoderMode);
124 
125  int8_t getEncoderMode();
126 
128 
129  void setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields);
130 
131  int getMaxEvalFields(void);
132 
133  void setMaxEvalFields(int _maxEvalFields);
134  void setScanAngleShift(double _scanAngleShift);//for NAV310 should be changed in only mirrord in comibantion with new scanangelshift param
135 
136  double getScanAngleShift();
137 
138  private:
139  std::string scannerName;
150  int8_t encoderMode;
156  };
157 
158 
160  {
161  public:
162  SickGenericParser(std::string scannerType);
163 
164  virtual ~SickGenericParser();
165 
166  virtual int parse_datagram(char *datagram, size_t datagram_length, SickScanConfig &config,
167  sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask);
168 
169 
170  void checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol);
171 
172  void set_range_min(float min);
173 
174  void set_range_max(float max);
175 
176  float get_range_min(void);
177 
178  float get_range_max(void);
179 
180  void set_time_increment(float time);
181 
182  void setScannerType(std::string s);
183 
184  std::string getScannerType(void);
185 
186  int lookUpForAllowedScanner(std::string scannerName);
187 
188  void setCurrentParamPtr(ScannerBasicParam *_ptr);
189 
190  ScannerBasicParam *getCurrentParamPtr();
191 
192 
193  int checkForDistAndRSSI(std::vector<char *> &fields, int expected_number_of_data, int &distNum, int &rssiNum,
194  std::vector<float> &distVal, std::vector<float> &rssiVal, int &distMask);
195 
196 
197  private:
198  float override_range_min_, override_range_max_;
200  std::string scannerType;
201  std::vector<std::string> allowedScannerNames;
202  std::vector<ScannerBasicParam> basicParams;
204  };
205 
206 } /* namespace sick_scan */
207 #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
bool getUseSafetyPasWD()
flag to mark the device uses the safety scanner password Bool true for safety password false for nor...
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)
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
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.
void setEncoderMode(int8_t _EncoderMode)
Prama for encoder mode.
void setScanMirroredAndShifted(bool _scanMirroredAndShifted)
flag to mark mirroring of rotation direction
int getNumberOfMaximumEchos(void)
Get number of maximum echoes for this laser scanner type.
void setMaxEvalFields(int _maxEvalFields)
void setUseSafetyPasWD(bool _useSafetyPasWD)
flag to mark the device uses the safety scanner password
void setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields)
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
void setScanAngleShift(double _scanAngleShift)
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
int8_t getEncoderMode()
Getter-Method for encoder mode.
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
EVAL_FIELD_SUPPORT getUseEvalFields()
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 Wed Sep 7 2022 02:25:06