sick_generic_parser.cpp
Go to the documentation of this file.
1 
50 #ifdef _MSC_VER
51 #pragma warning(disable: 4267)
52 #endif
53 
54 #define _CRT_SECURE_NO_WARNINGS
55 #define _USE_MATH_DEFINES
56 
57 #include <math.h>
59 #include <ros/ros.h>
60 
61 #ifdef _MSC_VER
62 #include "sick_scan/rosconsole_simu.hpp"
63 #endif
64 
65 namespace sick_scan
66 {
67  using namespace std;
68 
75  void ScannerBasicParam::setScannerName(std::string _s)
76  {
77  scannerName = _s;
78  }
79 
87  {
88  return (scannerName);
89  }
90 
91 
99  {
100  numberOfLayers = _layerNum;
101  }
102 
110  {
111  return (numberOfLayers);
112 
113  }
114 
122  {
123  numberOfShots = _shots;
124  }
125 
133  {
134  return (numberOfShots);
135  }
136 
144  {
145  this->numberOfMaximumEchos = _maxEchos;
146  }
147 
148 
156  {
157  return (numberOfMaximumEchos);
158  }
159 
167  {
168  currentParamSet = _ptr;
169  }
170 
171 
178  {
179  angleDegressResolution = _res;
180  }
181 
188  {
189  return (angleDegressResolution);
190  }
191 
198  {
199  expectedFrequency = _freq;
200  }
201 
209  {
210  return (expectedFrequency);
211  }
212 
213 
220  {
221  this->elevationDegreeResolution = _elevRes;
222  }
223 
224 
231  {
232  return (this->elevationDegreeResolution);
233  }
234 
241  {
242  this->useBinaryProtocol = _useBinary;
243  }
244 
250  void ScannerBasicParam::setDeviceIsRadar(bool _deviceIsRadar)
251  {
252  deviceIsRadar = _deviceIsRadar;
253  }
254 
261  {
262  return (deviceIsRadar);
263  }
264 
270  void ScannerBasicParam::setScanMirroredAndShifted(bool _scannMirroredAndShifted)
271  {
272  scanMirroredAndShifted = _scannMirroredAndShifted;
273  }
274 
281  {
282  return (scanMirroredAndShifted);
283  }
284 
291  {
292  return (this->useBinaryProtocol);
293  }
294 
300  void ScannerBasicParam::setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
301  {
302  this->IntensityResolutionIs16Bit = _IntensityResolutionIs16Bit;
303  }
304 
311  {
312  return (IntensityResolutionIs16Bit);
313  }
314 
320  void ScannerBasicParam::setUseSafetyPasWD(bool _useSafetyPasWD)
321  {
322  this->useSafetyPasWD = _useSafetyPasWD;
323  }
324 
331  {
332  return (useSafetyPasWD);
333  }
334 
336  {
337  return this->useEvalFields;
338  }
339 
341  {
342  this->useEvalFields = _useEvalFields;
343  }
344 
346  {
347  return this->maxEvalFields;
348  }
349 
350  void ScannerBasicParam::setMaxEvalFields(int _maxEvalFields)
351  {
352  this->maxEvalFields = _maxEvalFields;
353  }
354 
355 
361  : numberOfLayers(0), numberOfShots(0), numberOfMaximumEchos(0), elevationDegreeResolution(0), angleDegressResolution(0), expectedFrequency(0),
362  useBinaryProtocol(false), IntensityResolutionIs16Bit(false), deviceIsRadar(false), useSafetyPasWD(false), encoderMode(0),
363  CartographerCompatibility(false), scanMirroredAndShifted(false), useEvalFields(EVAL_FIELD_UNSUPPORTED), maxEvalFields(0)
364  {
365  this->elevationDegreeResolution = 0.0;
366  this->setUseBinaryProtocol(false);
367  }
368 
374  void ScannerBasicParam::setEncoderMode(int8_t _encoderMode)
375  {
376  this->encoderMode = _encoderMode;
377  }
378 
1026 
1050 
void setCurrentParamPtr(ScannerBasicParam *_ptr)
Set pointer to corresponding parameter object to the parser.
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
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
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.
ScannerBasicParam()
Construction of parameter object.
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
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()
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 May 5 2021 03:05:48