#include <sick_generic_parser.h>
Public Member Functions | |
double | getAngularDegreeResolution (void) |
Get angular resolution in degress. | |
bool | getDeviceIsRadar (void) |
flag to mark the device as radar (instead of laser scanner) | |
double | getElevationDegreeResolution (void) |
get angular resolution in VERTICAL direction for multilayer scanner | |
double | getExpectedFrequency (void) |
get expected scan frequency | |
bool | getIntensityResolutionIs16Bit (void) |
Get the RSSI Value length. | |
int | getNumberOfLayers (void) |
Getting number of scanner layers. | |
int | getNumberOfMaximumEchos (void) |
Get number of maximum echoes for this laser scanner type. | |
int | getNumberOfShots (void) |
Get number of shots per scan. | |
std::string | getScannerName (void) |
Getting name (type) of scanner. | |
bool | getUseBinaryProtocol (void) |
flag to decide between usage of ASCII-sopas or BINARY-sopas | |
ScannerBasicParam () | |
Construction of parameter object. | |
void | setAngularDegreeResolution (double _res) |
Set angular resolution in degrees. | |
void | setDeviceIsRadar (bool _deviceIsRadar) |
flag to mark the device as radar (instead of laser scanner) | |
void | setElevationDegreeResolution (double _elevRes) |
set angular resolution in VERTICAL direction for multilayer scanner | |
void | setExpectedFrequency (double _freq) |
set expected scan frequency | |
void | setIntensityResolutionIs16Bit (bool _IntensityResolutionIs16Bit) |
Set the RSSI Value length. | |
void | setNumberOfLayers (int _layerNum) |
Setting number of scanner layers (depending of scanner type/family) | |
void | setNumberOfMaximumEchos (int _maxEchos) |
Set number of maximum echoes for this laser scanner type. | |
void | setNumberOfShots (int _shots) |
Set number of shots per scan. | |
void | setScannerName (std::string _s) |
Setting name (type) of scanner. | |
void | setUseBinaryProtocol (bool _useBinary) |
flag to decide between usage of ASCII-sopas or BINARY-sopas | |
Private Attributes | |
double | angleDegressResolution |
bool | CartographerCompatibility |
bool | deviceIsRadar |
double | elevationDegreeResolution |
double | expectedFrequency |
bool | IntensityResolutionIs16Bit |
int | numberOfLayers |
int | numberOfMaximumEchos |
int | numberOfShots |
std::string | scannerName |
bool | useBinaryProtocol |
Definition at line 55 of file sick_generic_parser.h.
Construction of parameter object.
Definition at line 298 of file sick_generic_parser.cpp.
double sick_scan::ScannerBasicParam::getAngularDegreeResolution | ( | void | ) |
Get angular resolution in degress.
Definition at line 185 of file sick_generic_parser.cpp.
bool sick_scan::ScannerBasicParam::getDeviceIsRadar | ( | void | ) |
flag to mark the device as radar (instead of laser scanner)
_deviceIsRadar,: | false for laserscanner, true for radar (like rms_3xx) |
Definition at line 258 of file sick_generic_parser.cpp.
double sick_scan::ScannerBasicParam::getElevationDegreeResolution | ( | void | ) |
get angular resolution in VERTICAL direction for multilayer scanner
Definition at line 228 of file sick_generic_parser.cpp.
double sick_scan::ScannerBasicParam::getExpectedFrequency | ( | void | ) |
get expected scan frequency
Definition at line 206 of file sick_generic_parser.cpp.
Get the RSSI Value length.
Definition at line 287 of file sick_generic_parser.cpp.
int sick_scan::ScannerBasicParam::getNumberOfLayers | ( | void | ) |
Getting number of scanner layers.
Definition at line 107 of file sick_generic_parser.cpp.
Get number of maximum echoes for this laser scanner type.
Definition at line 153 of file sick_generic_parser.cpp.
int sick_scan::ScannerBasicParam::getNumberOfShots | ( | void | ) |
Get number of shots per scan.
Definition at line 130 of file sick_generic_parser.cpp.
std::string sick_scan::ScannerBasicParam::getScannerName | ( | void | ) |
Getting name (type) of scanner.
Definition at line 84 of file sick_generic_parser.cpp.
bool sick_scan::ScannerBasicParam::getUseBinaryProtocol | ( | void | ) |
flag to decide between usage of ASCII-sopas or BINARY-sopas
Definition at line 268 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setAngularDegreeResolution | ( | double | _res | ) |
Set angular resolution in degrees.
_res | resolution in degress (NOT rad) between each shot |
Definition at line 175 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setDeviceIsRadar | ( | bool | _deviceIsRadar | ) |
flag to mark the device as radar (instead of laser scanner)
_deviceIsRadar,: | false for laserscanner, true for radar (like rms_3xx) |
Definition at line 248 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setElevationDegreeResolution | ( | double | _elevRes | ) |
set angular resolution in VERTICAL direction for multilayer scanner
_elevRes | resolution in degree |
Definition at line 217 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setExpectedFrequency | ( | double | _freq | ) |
set expected scan frequency
_freq | scan frequency in [Hz] |
Definition at line 195 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setIntensityResolutionIs16Bit | ( | bool | _IntensityResolutionIs16Bit | ) |
Set the RSSI Value length.
_useBinary,: | Boolean value: True=16 Bit False=8Bit |
Definition at line 277 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setNumberOfLayers | ( | int | _layerNum | ) |
Setting number of scanner layers (depending of scanner type/family)
_layerNum | of scanner layers (e.g. 1 for TiM5xx and 24 for MRS6124 |
Definition at line 96 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setNumberOfMaximumEchos | ( | int | _maxEchos | ) |
Set number of maximum echoes for this laser scanner type.
_maxEchos | of max echoes |
Definition at line 141 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setNumberOfShots | ( | int | _shots | ) |
Set number of shots per scan.
_shots | of shots per scan (for one layer) |
Definition at line 119 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setScannerName | ( | std::string | _s | ) |
Setting name (type) of scanner.
_s | name of scanner |
Definition at line 73 of file sick_generic_parser.cpp.
void sick_scan::ScannerBasicParam::setUseBinaryProtocol | ( | bool | _useBinary | ) |
flag to decide between usage of ASCII-sopas or BINARY-sopas
_useBinary,: | True for binary, False for ASCII |
Definition at line 238 of file sick_generic_parser.cpp.
double sick_scan::ScannerBasicParam::angleDegressResolution [private] |
Definition at line 85 of file sick_generic_parser.h.
bool sick_scan::ScannerBasicParam::CartographerCompatibility [private] |
Definition at line 91 of file sick_generic_parser.h.
bool sick_scan::ScannerBasicParam::deviceIsRadar [private] |
Definition at line 89 of file sick_generic_parser.h.
double sick_scan::ScannerBasicParam::elevationDegreeResolution [private] |
Definition at line 84 of file sick_generic_parser.h.
double sick_scan::ScannerBasicParam::expectedFrequency [private] |
Definition at line 86 of file sick_generic_parser.h.
bool sick_scan::ScannerBasicParam::IntensityResolutionIs16Bit [private] |
Definition at line 88 of file sick_generic_parser.h.
int sick_scan::ScannerBasicParam::numberOfLayers [private] |
Definition at line 81 of file sick_generic_parser.h.
int sick_scan::ScannerBasicParam::numberOfMaximumEchos [private] |
Definition at line 83 of file sick_generic_parser.h.
int sick_scan::ScannerBasicParam::numberOfShots [private] |
Definition at line 82 of file sick_generic_parser.h.
std::string sick_scan::ScannerBasicParam::scannerName [private] |
Definition at line 80 of file sick_generic_parser.h.
bool sick_scan::ScannerBasicParam::useBinaryProtocol [private] |
Definition at line 87 of file sick_generic_parser.h.