Go to the documentation of this file.
35 #ifndef SICK_GENERIC_PARSER_H_
36 #define SICK_GENERIC_PARSER_H_
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"
55 #include "sensor_msgs/LaserScan.h"
166 virtual int parse_datagram(
char *datagram,
size_t datagram_length, SickScanConfig &config,
167 sensor_msgs::LaserScan &
msg,
int &numEchos,
int &echoMask);
170 void checkScanTiming(
float time_increment,
float scan_time,
float angle_increment,
float tol);
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);
std::string getScannerName(void)
Getting name (type) of scanner.
void setNumberOfMaximumEchos(int _maxEchos)
Set number of maximum echoes for this laser scanner type.
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
double getAngularDegreeResolution(void)
Get angular resolution in degress.
@ USE_EVAL_FIELD_LMS5XX_LOGIC
int lookUpForAllowedScanner(std::string scannerName)
checks the given scannerName/scannerType of validity
void setCurrentParamPtr(ScannerBasicParam *_ptr)
Set pointer to corresponding parameter object to the parser.
int8_t getEncoderMode()
Getter-Method for encoder mode.
@ USE_EVAL_FIELD_TIM7XX_LOGIC
void setScannerType(std::string s)
setting scannertype
int getMaxEvalFields(void)
float override_time_increment_
void setEncoderMode(int8_t _EncoderMode)
Prama for encoder mode.
bool getDeviceIsRadar(void)
flag to mark the device as radar (instead of laser scanner)
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
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
float override_range_max_
double getScanAngleShift()
bool CartographerCompatibility
void setExpectedFrequency(double _freq)
set expected scan frequency
void set_range_min(float min)
Setting minimum range.
void setMaxEvalFields(int _maxEvalFields)
ScannerBasicParam()
Construction of parameter object.
bool IntensityResolutionIs16Bit
SickGenericParser(std::string scannerType)
Construction of parser object.
ScannerBasicParam * currentParamSet
std::vector< ScannerBasicParam > basicParams
bool scanMirroredAndShifted
void setNumberOfShots(int _shots)
Set number of shots per scan.
void setElevationDegreeResolution(double _elevRes)
set angular resolution in VERTICAL direction for multilayer scanner
void checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol)
std::vector< std::string > allowedScannerNames
void setScannerName(std::string _s)
Setting name (type) of scanner.
EVAL_FIELD_SUPPORT getUseEvalFields()
int getNumberOfMaximumEchos(void)
Get number of maximum echoes for this laser scanner type.
float get_range_max(void)
Getting maximum range.
std::string getScannerType(void)
getting scannertype
void setDeviceIsRadar(bool _deviceIsRadar)
flag to mark the device as radar (instead of laser scanner)
float get_range_min(void)
Getting minimum range.
virtual int parse_datagram(char *datagram, size_t datagram_length, SickScanConfig &config, sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask)
Parsing Ascii datagram.
void setAngularDegreeResolution(double _res)
Set angular resolution in degrees.
void setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields)
double getElevationDegreeResolution(void)
get angular resolution in VERTICAL direction for multilayer scanner
int getNumberOfShots(void)
Get number of shots per scan.
bool getIntensityResolutionIs16Bit(void)
Get the RSSI Value length.
bool getUseSafetyPasWD()
flag to mark the device uses the safety scanner password \reutrn Bool true for safety password false ...
virtual ~SickGenericParser()
Destructor of parser.
double angleDegressResolution
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
EVAL_FIELD_SUPPORT useEvalFields
double getExpectedFrequency(void)
get expected scan frequency
double elevationDegreeResolution
void setScanAngleShift(double _scanAngleShift)
void setScanMirroredAndShifted(bool _scanMirroredAndShifted)
flag to mark mirroring of rotation direction
@ USE_EVAL_FIELD_LMS5XX_UNSUPPORTED
static sick_scan::SickScanCommonTcp * s
void set_range_max(float max)
Setting maximum range.
int getNumberOfLayers(void)
Getting number of scanner layers.
void setUseSafetyPasWD(bool _useSafetyPasWD)
flag to mark the device uses the safety scanner password
void set_time_increment(float time)
setting time increment between shots
void setUseBinaryProtocol(bool _useBinary)
flag to decide between usage of ASCII-sopas or BINARY-sopas
void setNumberOfLayers(int _layerNum)
Setting number of scanner layers (depending of scanner type/family)
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
float override_range_min_
sick_scan
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Thu Sep 8 2022 02:30:19