51 #pragma warning(disable: 4267) 54 #define _CRT_SECURE_NO_WARNINGS 55 #define _USE_MATH_DEFINES 62 #include "sick_scan/rosconsole_simu.hpp" 100 numberOfLayers = _layerNum;
111 return (numberOfLayers);
123 numberOfShots = _shots;
134 return (numberOfShots);
145 this->numberOfMaximumEchos = _maxEchos;
157 return (numberOfMaximumEchos);
168 currentParamSet = _ptr;
179 angleDegressResolution = _res;
189 return (angleDegressResolution);
199 expectedFrequency = _freq;
210 return (expectedFrequency);
221 this->elevationDegreeResolution = _elevRes;
232 return (this->elevationDegreeResolution);
242 this->useBinaryProtocol = _useBinary;
252 deviceIsRadar = _deviceIsRadar;
262 return (deviceIsRadar);
272 scanMirroredAndShifted = _scannMirroredAndShifted;
282 return (scanMirroredAndShifted);
292 return (this->useBinaryProtocol);
302 this->IntensityResolutionIs16Bit = _IntensityResolutionIs16Bit;
312 return (IntensityResolutionIs16Bit);
322 this->useSafetyPasWD = _useSafetyPasWD;
332 return (useSafetyPasWD);
337 return this->useEvalFields;
342 this->useEvalFields = _useEvalFields;
347 return this->maxEvalFields;
352 this->maxEvalFields = _maxEvalFields;
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)
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.
double elevationDegreeResolution
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
int getMaxEvalFields(void)
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)