Public Member Functions | Private Attributes | List of all members
sick_scan::ScannerBasicParam Class Reference

#include <sick_generic_parser.h>

Public Member Functions

double getAngularDegreeResolution (void)
 Get angular resolution in degress. More...
 
bool getDeviceIsRadar (void)
 flag to mark the device as radar (instead of laser scanner) More...
 
double getElevationDegreeResolution (void)
 get angular resolution in VERTICAL direction for multilayer scanner More...
 
int8_t getEncoderMode ()
 Getter-Method for encoder mode. More...
 
double getExpectedFrequency (void)
 get expected scan frequency More...
 
bool getIntensityResolutionIs16Bit (void)
 Get the RSSI Value length. More...
 
int getMaxEvalFields (void)
 
int getNumberOfLayers (void)
 Getting number of scanner layers. More...
 
int getNumberOfMaximumEchos (void)
 Get number of maximum echoes for this laser scanner type. More...
 
int getNumberOfShots (void)
 Get number of shots per scan. More...
 
bool getScanMirroredAndShifted ()
 flag to mark mirroring of rotation direction More...
 
std::string getScannerName (void)
 Getting name (type) of scanner. More...
 
bool getUseBinaryProtocol (void)
 flag to decide between usage of ASCII-sopas or BINARY-sopas More...
 
EVAL_FIELD_SUPPORT getUseEvalFields ()
 
bool getUseSafetyPasWD ()
 flag to mark the device uses the safety scanner password Bool true for safety password false for normal password More...
 
 ScannerBasicParam ()
 Construction of parameter object. More...
 
void setAngularDegreeResolution (double _res)
 Set angular resolution in degrees. More...
 
void setDeviceIsRadar (bool _deviceIsRadar)
 flag to mark the device as radar (instead of laser scanner) More...
 
void setElevationDegreeResolution (double _elevRes)
 set angular resolution in VERTICAL direction for multilayer scanner More...
 
void setEncoderMode (int8_t _EncoderMode)
 Prama for encoder mode. More...
 
void setExpectedFrequency (double _freq)
 set expected scan frequency More...
 
void setIntensityResolutionIs16Bit (bool _IntensityResolutionIs16Bit)
 Set the RSSI Value length. More...
 
void setMaxEvalFields (int _maxEvalFields)
 
void setNumberOfLayers (int _layerNum)
 Setting number of scanner layers (depending of scanner type/family) More...
 
void setNumberOfMaximumEchos (int _maxEchos)
 Set number of maximum echoes for this laser scanner type. More...
 
void setNumberOfShots (int _shots)
 Set number of shots per scan. More...
 
void setScanMirroredAndShifted (bool _scanMirroredAndShifted)
 flag to mark mirroring of rotation direction More...
 
void setScannerName (std::string _s)
 Setting name (type) of scanner. More...
 
void setUseBinaryProtocol (bool _useBinary)
 flag to decide between usage of ASCII-sopas or BINARY-sopas More...
 
void setUseEvalFields (EVAL_FIELD_SUPPORT _useEvalFields)
 
void setUseSafetyPasWD (bool _useSafetyPasWD)
 flag to mark the device uses the safety scanner password More...
 

Private Attributes

double angleDegressResolution
 
bool CartographerCompatibility
 
bool deviceIsRadar
 
double elevationDegreeResolution
 
int8_t encoderMode
 
double expectedFrequency
 
bool IntensityResolutionIs16Bit
 
int maxEvalFields
 
int numberOfLayers
 
int numberOfMaximumEchos
 
int numberOfShots
 
bool scanMirroredAndShifted
 
std::string scannerName
 
bool useBinaryProtocol
 
EVAL_FIELD_SUPPORT useEvalFields
 
bool useSafetyPasWD
 

Detailed Description

Definition at line 70 of file sick_generic_parser.h.

Constructor & Destructor Documentation

sick_scan::ScannerBasicParam::ScannerBasicParam ( )

Construction of parameter object.

Definition at line 360 of file sick_generic_parser.cpp.

Member Function Documentation

double sick_scan::ScannerBasicParam::getAngularDegreeResolution ( void  )

Get angular resolution in degress.

Returns
angle resolution in degress (NOT rad) between each shot

Definition at line 187 of file sick_generic_parser.cpp.

bool sick_scan::ScannerBasicParam::getDeviceIsRadar ( void  )

flag to mark the device as radar (instead of laser scanner)

Parameters
_deviceIsRadarfalse for laserscanner, true for radar (like rms_3xx)
See also
getDeviceIsRadar

Definition at line 260 of file sick_generic_parser.cpp.

double sick_scan::ScannerBasicParam::getElevationDegreeResolution ( void  )

get angular resolution in VERTICAL direction for multilayer scanner

Returns
elevation resolution in degree
See also
setElevationDegreeResolution

Definition at line 230 of file sick_generic_parser.cpp.

int8_t sick_scan::ScannerBasicParam::getEncoderMode ( )

Getter-Method for encoder mode.

/*!

Returns
EncoderMode:-1 Use for Scanners WO Encoder 00 disabled 01 single increment 02 direction recognition phase 03 direction recognition level
See also
setEncoderMode

Definition at line 385 of file sick_generic_parser.cpp.

double sick_scan::ScannerBasicParam::getExpectedFrequency ( void  )

get expected scan frequency

Returns
expected scan frequency in [Hz]
See also
setExpectedFrequency

Definition at line 208 of file sick_generic_parser.cpp.

bool sick_scan::ScannerBasicParam::getIntensityResolutionIs16Bit ( void  )

Get the RSSI Value length.

Returns
Boolean value: True=16 Bit False=8Bit
See also
setUseBinaryProtocol

Definition at line 310 of file sick_generic_parser.cpp.

int sick_scan::ScannerBasicParam::getMaxEvalFields ( void  )

Definition at line 345 of file sick_generic_parser.cpp.

int sick_scan::ScannerBasicParam::getNumberOfLayers ( void  )

Getting number of scanner layers.

Returns
Number of scanners layer (e.g. 1 for TiM5xx and 24 for MRS6124)
See also
setNumberOfLayers

Definition at line 109 of file sick_generic_parser.cpp.

int sick_scan::ScannerBasicParam::getNumberOfMaximumEchos ( void  )

Get number of maximum echoes for this laser scanner type.

Returns
Number of max echoes
See also
setNumberOfMaximumEchos

Definition at line 155 of file sick_generic_parser.cpp.

int sick_scan::ScannerBasicParam::getNumberOfShots ( void  )

Get number of shots per scan.

Returns
Number of shots per scan (for one layer)
See also
getNumberOfLayers

Definition at line 132 of file sick_generic_parser.cpp.

bool sick_scan::ScannerBasicParam::getScanMirroredAndShifted ( void  )

flag to mark mirroring of rotation direction

Parameters
_scanMirroredfalse for normal mounting true for up side down or NAV 310
See also
getScanMirrored

Definition at line 280 of file sick_generic_parser.cpp.

std::string sick_scan::ScannerBasicParam::getScannerName ( void  )

Getting name (type) of scanner.

Returns
Name of scanner
See also
setScannerName

Definition at line 86 of file sick_generic_parser.cpp.

bool sick_scan::ScannerBasicParam::getUseBinaryProtocol ( void  )

flag to decide between usage of ASCII-sopas or BINARY-sopas

Returns
_useBinary: True for binary, False for ASCII
See also
getUseBinaryProtocol

Definition at line 290 of file sick_generic_parser.cpp.

EVAL_FIELD_SUPPORT sick_scan::ScannerBasicParam::getUseEvalFields ( )

Definition at line 335 of file sick_generic_parser.cpp.

bool sick_scan::ScannerBasicParam::getUseSafetyPasWD ( )

flag to mark the device uses the safety scanner password Bool true for safety password false for normal password

See also
getUseSafetyPasWD

Definition at line 330 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setAngularDegreeResolution ( double  _res)

Set angular resolution in degrees.

Parameters
_resresolution in degress (NOT rad) between each shot
See also
getAngularDegreeResolution

Definition at line 177 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setDeviceIsRadar ( bool  _deviceIsRadar)

flag to mark the device as radar (instead of laser scanner)

Parameters
_deviceIsRadarfalse for laserscanner, true for radar (like rms_3xx)
See also
getDeviceIsRadar

Definition at line 250 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setElevationDegreeResolution ( double  _elevRes)

set angular resolution in VERTICAL direction for multilayer scanner

Parameters
_elevResresolution in degree
See also
getElevationDegreeResolution

Definition at line 219 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setEncoderMode ( int8_t  _encoderMode)

Prama for encoder mode.

Parameters
_EncoderMode-1 Use for Scanners WO Encoder 00 disabled 01 single increment 02 direction recognition phase 03 direction recognition level
See also
setEncoderMode

Definition at line 374 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setExpectedFrequency ( double  _freq)

set expected scan frequency

Parameters
_freqscan frequency in [Hz]
See also
getExpectedFrequency

Definition at line 197 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setIntensityResolutionIs16Bit ( bool  _IntensityResolutionIs16Bit)

Set the RSSI Value length.

Parameters
_useBinaryBoolean value: True=16 Bit False=8Bit
See also
getUseBinaryProtocol

Definition at line 300 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setMaxEvalFields ( int  _maxEvalFields)

Definition at line 350 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setNumberOfLayers ( int  _layerNum)

Setting number of scanner layers (depending of scanner type/family)

Parameters
_layerNumof scanner layers (e.g. 1 for TiM5xx and 24 for MRS6124
See also
getNumberOfLayers

Definition at line 98 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setNumberOfMaximumEchos ( int  _maxEchos)

Set number of maximum echoes for this laser scanner type.

Parameters
_maxEchosof max echoes
See also
getNumberOfMaximumEchos

Definition at line 143 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setNumberOfShots ( int  _shots)

Set number of shots per scan.

Parameters
_shotsof shots per scan (for one layer)
See also
getNumberOfLayers

Definition at line 121 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setScanMirroredAndShifted ( bool  _scannMirroredAndShifted)

flag to mark mirroring of rotation direction

Parameters
_scanMirroredfalse for normal mounting true for up side down or NAV 310
See also
setScanMirrored

Definition at line 270 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setScannerName ( std::string  _s)

Setting name (type) of scanner.

Parameters
_sname of scanner
See also
getScannerName

Definition at line 75 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setUseBinaryProtocol ( bool  _useBinary)

flag to decide between usage of ASCII-sopas or BINARY-sopas

Parameters
_useBinaryTrue for binary, False for ASCII
See also
getUseBinaryProtocol

Definition at line 240 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setUseEvalFields ( EVAL_FIELD_SUPPORT  _useEvalFields)

Definition at line 340 of file sick_generic_parser.cpp.

void sick_scan::ScannerBasicParam::setUseSafetyPasWD ( bool  _useSafetyPasWD)

flag to mark the device uses the safety scanner password

Parameters
_useSafetyPasWDfalse for normal scanners true for safety scanners
See also
setUseSafetyPasWD

Definition at line 320 of file sick_generic_parser.cpp.

Member Data Documentation

double sick_scan::ScannerBasicParam::angleDegressResolution
private

Definition at line 141 of file sick_generic_parser.h.

bool sick_scan::ScannerBasicParam::CartographerCompatibility
private

Definition at line 148 of file sick_generic_parser.h.

bool sick_scan::ScannerBasicParam::deviceIsRadar
private

Definition at line 145 of file sick_generic_parser.h.

double sick_scan::ScannerBasicParam::elevationDegreeResolution
private

Definition at line 140 of file sick_generic_parser.h.

int8_t sick_scan::ScannerBasicParam::encoderMode
private

Definition at line 147 of file sick_generic_parser.h.

double sick_scan::ScannerBasicParam::expectedFrequency
private

Definition at line 142 of file sick_generic_parser.h.

bool sick_scan::ScannerBasicParam::IntensityResolutionIs16Bit
private

Definition at line 144 of file sick_generic_parser.h.

int sick_scan::ScannerBasicParam::maxEvalFields
private

Definition at line 151 of file sick_generic_parser.h.

int sick_scan::ScannerBasicParam::numberOfLayers
private

Definition at line 137 of file sick_generic_parser.h.

int sick_scan::ScannerBasicParam::numberOfMaximumEchos
private

Definition at line 139 of file sick_generic_parser.h.

int sick_scan::ScannerBasicParam::numberOfShots
private

Definition at line 138 of file sick_generic_parser.h.

bool sick_scan::ScannerBasicParam::scanMirroredAndShifted
private

Definition at line 149 of file sick_generic_parser.h.

std::string sick_scan::ScannerBasicParam::scannerName
private

Definition at line 136 of file sick_generic_parser.h.

bool sick_scan::ScannerBasicParam::useBinaryProtocol
private

Definition at line 143 of file sick_generic_parser.h.

EVAL_FIELD_SUPPORT sick_scan::ScannerBasicParam::useEvalFields
private

Definition at line 150 of file sick_generic_parser.h.

bool sick_scan::ScannerBasicParam::useSafetyPasWD
private

Definition at line 146 of file sick_generic_parser.h.


The documentation for this class was generated from the following files:


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Wed May 5 2021 03:05:49