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 
189 
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:
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_ */
sick_scan::ScannerBasicParam::getScannerName
std::string getScannerName(void)
Getting name (type) of scanner.
Definition: sick_generic_parser.cpp:86
sick_scan::ScannerBasicParam::setNumberOfMaximumEchos
void setNumberOfMaximumEchos(int _maxEchos)
Set number of maximum echoes for this laser scanner type.
Definition: sick_generic_parser.cpp:143
min
int min(int a, int b)
sick_scan::ScannerBasicParam::getScanMirroredAndShifted
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
Definition: sick_generic_parser.cpp:280
msg
msg
sick_scan::ScannerBasicParam::getAngularDegreeResolution
double getAngularDegreeResolution(void)
Get angular resolution in degress.
Definition: sick_generic_parser.cpp:187
sick_scan::USE_EVAL_FIELD_LMS5XX_LOGIC
@ USE_EVAL_FIELD_LMS5XX_LOGIC
Definition: sick_generic_parser.h:65
sick_scan::SickGenericParser::scannerType
std::string scannerType
Definition: sick_generic_parser.h:200
sick_scan::EVAL_FIELD_SUPPORT
EVAL_FIELD_SUPPORT
Definition: sick_generic_parser.h:61
sick_scan::SickGenericParser::lookUpForAllowedScanner
int lookUpForAllowedScanner(std::string scannerName)
checks the given scannerName/scannerType of validity
Definition: sick_generic_parser.cpp:693
sick_scan::ScannerBasicParam::scannerName
std::string scannerName
Definition: sick_generic_parser.h:139
sick_scan::ScannerBasicParam::expectedFrequency
double expectedFrequency
Definition: sick_generic_parser.h:145
sick_scan::SickGenericParser::setCurrentParamPtr
void setCurrentParamPtr(ScannerBasicParam *_ptr)
Set pointer to corresponding parameter object to the parser.
Definition: sick_generic_parser.cpp:166
sick_scan::ScannerBasicParam::getEncoderMode
int8_t getEncoderMode()
Getter-Method for encoder mode.
Definition: sick_generic_parser.cpp:395
sick_scan::USE_EVAL_FIELD_TIM7XX_LOGIC
@ USE_EVAL_FIELD_TIM7XX_LOGIC
Definition: sick_generic_parser.h:64
sick_scan::SickGenericParser
Definition: sick_generic_parser.h:159
sick_scan::ScannerBasicParam::numberOfMaximumEchos
int numberOfMaximumEchos
Definition: sick_generic_parser.h:142
sick_scan::SickGenericParser::setScannerType
void setScannerType(std::string s)
setting scannertype
Definition: sick_generic_parser.cpp:1234
sick_scan::ScannerBasicParam::getMaxEvalFields
int getMaxEvalFields(void)
Definition: sick_generic_parser.cpp:345
sick_scan::SickGenericParser::override_time_increment_
float override_time_increment_
Definition: sick_generic_parser.h:199
sick_scan::ScannerBasicParam::setEncoderMode
void setEncoderMode(int8_t _EncoderMode)
Prama for encoder mode.
Definition: sick_generic_parser.cpp:384
sick_scan::ScannerBasicParam::getDeviceIsRadar
bool getDeviceIsRadar(void)
flag to mark the device as radar (instead of laser scanner)
Definition: sick_generic_parser.cpp:260
sick_scan::EVAL_FIELD_UNSUPPORTED
@ EVAL_FIELD_UNSUPPORTED
Definition: sick_generic_parser.h:63
abstract_parser.h
sick_scan::SickGenericParser::checkForDistAndRSSI
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)
check for DIST and RSSI-entries in the datagram. Helper routine for parser
Definition: sick_generic_parser.cpp:728
sick_scan::ScannerBasicParam::setIntensityResolutionIs16Bit
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
Definition: sick_generic_parser.cpp:300
sick_scan::ScannerBasicParam
Definition: sick_generic_parser.h:70
sick_scan::AbstractParser
Definition: abstract_parser.h:51
sick_scan_common.h
sick_scan::SickGenericParser::override_range_max_
float override_range_max_
Definition: sick_generic_parser.h:198
sick_scan::ScannerBasicParam::getScanAngleShift
double getScanAngleShift()
Definition: sick_generic_parser.cpp:360
sick_scan::ScannerBasicParam::CartographerCompatibility
bool CartographerCompatibility
Definition: sick_generic_parser.h:151
sick_scan::ScannerBasicParam::setExpectedFrequency
void setExpectedFrequency(double _freq)
set expected scan frequency
Definition: sick_generic_parser.cpp:197
sick_scan::SickGenericParser::set_range_min
void set_range_min(float min)
Setting minimum range.
Definition: sick_generic_parser.cpp:1182
sick_scan::ScannerBasicParam::setMaxEvalFields
void setMaxEvalFields(int _maxEvalFields)
Definition: sick_generic_parser.cpp:350
sick_scan::ScannerBasicParam::ScannerBasicParam
ScannerBasicParam()
Construction of parameter object.
Definition: sick_generic_parser.cpp:370
sick_scan::USE_EVAL_FIELD_NUM
@ USE_EVAL_FIELD_NUM
Definition: sick_generic_parser.h:67
sick_scan::ScannerBasicParam::IntensityResolutionIs16Bit
bool IntensityResolutionIs16Bit
Definition: sick_generic_parser.h:147
sick_scan::SickGenericParser::SickGenericParser
SickGenericParser(std::string scannerType)
Construction of parser object.
Definition: sick_generic_parser.cpp:405
sick_scan::ScannerBasicParam::numberOfLayers
int numberOfLayers
Definition: sick_generic_parser.h:140
sick_scan::SickGenericParser::currentParamSet
ScannerBasicParam * currentParamSet
Definition: sick_generic_parser.h:203
sick_scan::SickGenericParser::basicParams
std::vector< ScannerBasicParam > basicParams
Definition: sick_generic_parser.h:202
sick_scan::ScannerBasicParam::scanMirroredAndShifted
bool scanMirroredAndShifted
Definition: sick_generic_parser.h:152
sick_scan::ScannerBasicParam::setNumberOfShots
void setNumberOfShots(int _shots)
Set number of shots per scan.
Definition: sick_generic_parser.cpp:121
sick_scan::ScannerBasicParam::setElevationDegreeResolution
void setElevationDegreeResolution(double _elevRes)
set angular resolution in VERTICAL direction for multilayer scanner
Definition: sick_generic_parser.cpp:219
sick_scan::SickGenericParser::checkScanTiming
void checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol)
Definition: sick_generic_parser.cpp:817
sick_scan::SickGenericParser::allowedScannerNames
std::vector< std::string > allowedScannerNames
Definition: sick_generic_parser.h:201
sick_scan::ScannerBasicParam::setScannerName
void setScannerName(std::string _s)
Setting name (type) of scanner.
Definition: sick_generic_parser.cpp:75
sick_scan
Definition: abstract_parser.cpp:50
sick_scan::ScannerBasicParam::getUseEvalFields
EVAL_FIELD_SUPPORT getUseEvalFields()
Definition: sick_generic_parser.cpp:335
sick_scan::ScannerBasicParam::scanAngleShift
double scanAngleShift
Definition: sick_generic_parser.h:155
sick_scan::ScannerBasicParam::getNumberOfMaximumEchos
int getNumberOfMaximumEchos(void)
Get number of maximum echoes for this laser scanner type.
Definition: sick_generic_parser.cpp:155
sick_scan::SickGenericParser::get_range_max
float get_range_max(void)
Getting maximum range.
Definition: sick_generic_parser.cpp:1203
sick_scan::SickGenericParser::getScannerType
std::string getScannerType(void)
getting scannertype
Definition: sick_generic_parser.cpp:1244
sick_scan::ScannerBasicParam::setDeviceIsRadar
void setDeviceIsRadar(bool _deviceIsRadar)
flag to mark the device as radar (instead of laser scanner)
Definition: sick_generic_parser.cpp:250
sick_scan::SickGenericParser::get_range_min
float get_range_min(void)
Getting minimum range.
Definition: sick_generic_parser.cpp:1213
sick_scan::SickGenericParser::parse_datagram
virtual int parse_datagram(char *datagram, size_t datagram_length, SickScanConfig &config, sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask)
Parsing Ascii datagram.
Definition: sick_generic_parser.cpp:847
sick_scan::ScannerBasicParam::setAngularDegreeResolution
void setAngularDegreeResolution(double _res)
Set angular resolution in degrees.
Definition: sick_generic_parser.cpp:177
sick_scan::ScannerBasicParam::encoderMode
int8_t encoderMode
Definition: sick_generic_parser.h:150
sick_scan::ScannerBasicParam::setUseEvalFields
void setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields)
Definition: sick_generic_parser.cpp:340
sick_scan::ScannerBasicParam::deviceIsRadar
bool deviceIsRadar
Definition: sick_generic_parser.h:148
sick_scan::ScannerBasicParam::getElevationDegreeResolution
double getElevationDegreeResolution(void)
get angular resolution in VERTICAL direction for multilayer scanner
Definition: sick_generic_parser.cpp:230
sick_scan::ScannerBasicParam::getNumberOfShots
int getNumberOfShots(void)
Get number of shots per scan.
Definition: sick_generic_parser.cpp:132
sick_scan::ScannerBasicParam::getIntensityResolutionIs16Bit
bool getIntensityResolutionIs16Bit(void)
Get the RSSI Value length.
Definition: sick_generic_parser.cpp:310
sick_scan::ScannerBasicParam::getUseSafetyPasWD
bool getUseSafetyPasWD()
flag to mark the device uses the safety scanner password \reutrn Bool true for safety password false ...
Definition: sick_generic_parser.cpp:330
sick_scan::SickGenericParser::~SickGenericParser
virtual ~SickGenericParser()
Destructor of parser.
Definition: sick_generic_parser.cpp:711
dataDumper.h
sick_scan::ScannerBasicParam::maxEvalFields
int maxEvalFields
Definition: sick_generic_parser.h:154
sick_scan::ScannerBasicParam::angleDegressResolution
double angleDegressResolution
Definition: sick_generic_parser.h:144
sick_scan::SickGenericParser::getCurrentParamPtr
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
Definition: sick_generic_parser.cpp:683
sick_scan::ScannerBasicParam::useEvalFields
EVAL_FIELD_SUPPORT useEvalFields
Definition: sick_generic_parser.h:153
sick_scan::ScannerBasicParam::getExpectedFrequency
double getExpectedFrequency(void)
get expected scan frequency
Definition: sick_generic_parser.cpp:208
sick_scan::ScannerBasicParam::elevationDegreeResolution
double elevationDegreeResolution
Definition: sick_generic_parser.h:143
sick_scan::ScannerBasicParam::setScanAngleShift
void setScanAngleShift(double _scanAngleShift)
Definition: sick_generic_parser.cpp:355
sick_scan::ScannerBasicParam::setScanMirroredAndShifted
void setScanMirroredAndShifted(bool _scanMirroredAndShifted)
flag to mark mirroring of rotation direction
Definition: sick_generic_parser.cpp:270
sick_scan::USE_EVAL_FIELD_LMS5XX_UNSUPPORTED
@ USE_EVAL_FIELD_LMS5XX_UNSUPPORTED
Definition: sick_generic_parser.h:66
sick_scan::ScannerBasicParam::numberOfShots
int numberOfShots
Definition: sick_generic_parser.h:141
s
static sick_scan::SickScanCommonTcp * s
Definition: sick_generic_laser.cpp:92
sick_scan::SickGenericParser::set_range_max
void set_range_max(float max)
Setting maximum range.
Definition: sick_generic_parser.cpp:1192
sick_scan::ScannerBasicParam::getNumberOfLayers
int getNumberOfLayers(void)
Getting number of scanner layers.
Definition: sick_generic_parser.cpp:109
sick_scan::ScannerBasicParam::useBinaryProtocol
bool useBinaryProtocol
Definition: sick_generic_parser.h:146
sick_scan::ScannerBasicParam::setUseSafetyPasWD
void setUseSafetyPasWD(bool _useSafetyPasWD)
flag to mark the device uses the safety scanner password
Definition: sick_generic_parser.cpp:320
sick_scan::SickGenericParser::set_time_increment
void set_time_increment(float time)
setting time increment between shots
Definition: sick_generic_parser.cpp:1223
sick_scan::ScannerBasicParam::setUseBinaryProtocol
void setUseBinaryProtocol(bool _useBinary)
flag to decide between usage of ASCII-sopas or BINARY-sopas
Definition: sick_generic_parser.cpp:240
sick_scan::ScannerBasicParam::setNumberOfLayers
void setNumberOfLayers(int _layerNum)
Setting number of scanner layers (depending of scanner type/family)
Definition: sick_generic_parser.cpp:98
sick_scan::ScannerBasicParam::getUseBinaryProtocol
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
Definition: sick_generic_parser.cpp:290
sick_scan::SickGenericParser::override_range_min_
float override_range_min_
Definition: sick_generic_parser.h:198
sick_scan::ScannerBasicParam::useSafetyPasWD
bool useSafetyPasWD
Definition: sick_generic_parser.h:149


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Thu Sep 8 2022 02:30:19