Go to the documentation of this file.
57 #ifndef SICK_GENERIC_PARSER_H_
58 #define SICK_GENERIC_PARSER_H_
63 #define SICK_SCANNER_LMS_1XXX_NAME "sick_lms_1xxx"
64 #define SICK_SCANNER_MRS_1XXX_NAME "sick_mrs_1xxx"
65 #define SICK_SCANNER_TIM_240_NAME "sick_tim_240"
66 #define SICK_SCANNER_TIM_5XX_NAME "sick_tim_5xx"
67 #define SICK_SCANNER_TIM_7XX_NAME "sick_tim_7xx"
68 #define SICK_SCANNER_TIM_7XXS_NAME "sick_tim_7xxS"
69 #define SICK_SCANNER_LMS_5XX_NAME "sick_lms_5xx"
70 #define SICK_SCANNER_LMS_1XX_NAME "sick_lms_1xx"
71 #define SICK_SCANNER_MRS_6XXX_NAME "sick_mrs_6xxx"
72 #define SICK_SCANNER_LMS_4XXX_NAME "sick_lms_4xxx"
73 #define SICK_SCANNER_RMS_XXXX_NAME "sick_rms_xxxx" // supports RMS-1xxx and RMS-2xxx
74 #define SICK_SCANNER_NAV_31X_NAME "sick_nav_31x"
75 #define SICK_SCANNER_NAV_350_NAME "sick_nav_350"
76 #define SICK_SCANNER_NAV_2XX_NAME "sick_nav_2xx"
77 #define SICK_SCANNER_TIM_4XX_NAME "sick_tim_4xx"
78 #define SICK_SCANNER_LRS_4XXX_NAME "sick_lrs_4xxx"
79 #define SICK_SCANNER_LRS_36x0_NAME "sick_lrs_36x0"
80 #define SICK_SCANNER_LRS_36x1_NAME "sick_lrs_36x1"
81 #define SICK_SCANNER_OEM_15XX_NAME "sick_oem_15xx"
82 #define SICK_SCANNER_SCANSEGMENT_XD_NAME "sick_multiscan" // "sick_scansegment_xd", multiScan136
83 #define SICK_SCANNER_PICOSCAN_NAME "sick_picoscan" // picoScan150, part of sick_scansegment_xd family
250 bool checkScanTiming(
float time_increment,
float scan_time,
float angle_increment,
float tol);
278 int checkForDistAndRSSI(std::vector<char *> &fields,
int expected_number_of_data,
int &distNum,
int &rssiNum,
279 std::vector<float> &distVal, std::vector<float> &rssiVal,
int &distMask);
virtual int parse_datagram(char *datagram, size_t datagram_length, SickScanConfig &config, ros_sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask)
Parsing Ascii datagram.
void setAngularDegreeResolution(double _res)
Set angular resolution in degrees.
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
void setElevationDegreeResolution(double _elevRes)
set angular resolution in VERTICAL direction for multilayer scanner
void setUseEvalFields(EVAL_FIELD_SUPPORT _useEvalFields)
int getNumberOfLayers(void)
Getting number of scanner layers.
void set_range_max(float max)
Setting maximum range.
void setScanAngleShift(double _scanAngleShift)
void setMaxEvalFields(int _maxEvalFields)
void setImuEnabled(bool _imuEnabled)
bool scandatacfgAzimuthTableSupported
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
double getExpectedFrequency(void)
get expected scan frequency
std::string getScannerName(void) const
Getting name (type) of scanner.
void setRectEvalFieldAngleRefPointOffsetRad(float _rectFieldAngleRefPointOffsetRad)
EVAL_FIELD_SUPPORT useEvalFields
int getNumberOfShots(void)
Get number of shots per scan.
void setTrackingModeSupported(bool _trackingModeSupported)
void setScannerType(std::string s)
setting scannertype
bool checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol)
void setDeviceIsRadar(RADAR_TYPE_ENUM _radar_type)
flag to mark the device as radar (instead of laser scanner)
void set_time_increment(float time)
setting time increment between shots
double getElevationDegreeResolution(void)
get angular resolution in VERTICAL direction for multilayer scanner
@ USE_EVAL_FIELD_LMS5XX_UNSUPPORTED
int8_t getEncoderMode()
Getter-Method for encoder mode.
void setScannerName(std::string _s)
Setting name (type) of 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 setNumberOfMaximumEchos(int _maxEchos)
Set number of maximum echoes for this laser scanner type.
void setUseScancfgList(bool _useScancfgList)
::sensor_msgs::LaserScan_< std::allocator< void > > LaserScan
float override_range_max_
double getScanAngleShift()
void setNumberOfLayers(int _layerNum)
Setting number of scanner layers (depending of scanner type/family)
void setUseBinaryProtocol(bool _useBinary)
flag to decide between usage of ASCII-sopas or BINARY-sopas
void setScandatacfgAzimuthTableSupported(bool _scandatacfgAzimuthTableSupported)
virtual ~SickGenericParser()
Destructor of parser.
void setCurrentParamPtr(ScannerBasicParam *_ptr)
Set pointer to corresponding parameter object to the parser.
bool getUseWriteOutputRanges()
float rectFieldAngleRefPointOffsetRad
SickGenericParser(std::string scannerType)
Construction of parser object.
int getNumberOfMaximumEchos(void)
Get number of maximum echoes for this laser scanner type.
double getAngularDegreeResolution(void)
Get angular resolution in degress.
bool scanMirroredAndShifted
float override_range_min_
bool IntensityResolutionIs16Bit
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
bool frEchoFilterAvailable
std::vector< std::string > allowedScannerNames
float get_time_increment(void)
getting time increment between shots
void setScanMirroredAndShifted(bool _scanMirroredAndShifted)
flag to mark mirroring of rotation direction
void setWaitForReady(bool _waitForReady)
bool isOneOfScannerNames(const std::vector< std::string > &scanner_names) const
Returns true, if the scanner name (type) is found int a given list of scanner names.
bool getFREchoFilterAvailable(void)
void set_range_min(float min)
Setting minimum range.
void setNumberOfShots(int _shots)
Set number of shots per scan.
@ USE_EVAL_FIELD_LMS5XX_LOGIC
void setUseWriteOutputRanges(bool _useWriteOutputRanges)
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
ScannerBasicParam()
Construction of parameter object.
ScannerBasicParam * currentParamSet
bool useWriteOutputRanges
std::string getScannerType(void)
getting scannertype
bool getIntensityResolutionIs16Bit(void)
Get the RSSI Value length.
int lookUpForAllowedScanner(std::string scannerName)
checks the given scannerName/scannerType of validity
void setFREchoFilterAvailable(bool _frEchoFilterAvailable)
float get_range_max(void)
Getting maximum range.
EVAL_FIELD_SUPPORT getUseEvalFields()
void setExpectedFrequency(double _freq)
set expected scan frequency
double angleDegressResolution
RADAR_TYPE_ENUM deviceRadarType
std::vector< ScannerBasicParam > basicParams
bool getTrackingModeSupported(void)
set/get flag to mark the radar device supports selection of tracking modes. By default,...
RangeFilterResultHandling m_range_filter_handling
void setEncoderMode(int8_t _EncoderMode)
Prama for encoder mode.
float get_range_min(void)
Getting minimum range.
bool getScandatacfgAzimuthTableSupported(void) const
double elevationDegreeResolution
void set_range_filter_config(RangeFilterResultHandling range_filter_handling)
Set range filter handling (range filter deactivated, drop, set to nan, etc.pp.)
enum sick_scan_xd::RangeFilterResultHandlingEnum RangeFilterResultHandling
bool getDeviceIsRadar(void)
flag to mark the device as radar (instead of laser scanner)
bool CartographerCompatibility
void setUseSafetyPasWD(bool _useSafetyPasWD)
flag to mark the device uses the safety scanner password
bool trackingModeSupported
int getMaxEvalFields(void)
float getRectEvalFieldAngleRefPointOffsetRad(void)
RangeFilterResultHandling get_range_filter_config(void) const
Get range filter handling (range filter deactivated, drop, set to nan, etc.pp.)
bool getUseSafetyPasWD()
flag to mark the device uses the safety scanner password \reutrn Bool true for safety password false ...
@ USE_EVAL_FIELD_TIM7XX_LOGIC
@ RANGE_FILTER_DEACTIVATED
float override_time_increment_
RADAR_TYPE_ENUM getDeviceRadarType(void)
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10