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" 162 virtual int parse_datagram(
char *datagram,
size_t datagram_length, SickScanConfig &config,
163 sensor_msgs::LaserScan &
msg,
int &numEchos,
int &echoMask);
166 void checkScanTiming(
float time_increment,
float scan_time,
float angle_increment,
float tol);
168 void set_range_min(
float min);
170 void set_range_max(
float max);
172 float get_range_min(
void);
174 float get_range_max(
void);
176 void set_time_increment(
float time);
178 void setScannerType(std::string
s);
180 std::string getScannerType(
void);
182 int lookUpForAllowedScanner(std::string
scannerName);
189 int checkForDistAndRSSI(std::vector<char *> &fields,
int expected_number_of_data,
int &distNum,
int &rssiNum,
190 std::vector<float> &distVal, std::vector<float> &rssiVal,
int &distMask);
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
ScannerBasicParam * currentParamSet
void setDeviceIsRadar(bool _deviceIsRadar)
flag to mark the device as radar (instead of laser scanner)
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
bool IntensityResolutionIs16Bit
int getNumberOfShots(void)
Get number of shots per scan.
bool CartographerCompatibility
float override_time_increment_
bool scanMirroredAndShifted
double elevationDegreeResolution
EVAL_FIELD_SUPPORT useEvalFields
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.
float override_range_min_
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 angleDegressResolution
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.
std::vector< std::string > allowedScannerNames
int8_t getEncoderMode()
Getter-Method for encoder mode.
ScannerBasicParam()
Construction of parameter object.
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
std::vector< ScannerBasicParam > basicParams
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()
static sick_scan::SickScanCommonTcp * s
bool getDeviceIsRadar(void)
flag to mark the device as radar (instead of laser scanner)