SickLMS2xx.hh
Go to the documentation of this file.
1 
15 #ifndef SICK_LMS_2XX_HH
16 #define SICK_LMS_2XX_HH
17 
18 /* Implementation dependencies */
19 #include <string>
20 #include <iostream>
21 #include <termios.h>
22 
23 #include "SickLIDAR.hh"
24 #include "SickException.hh"
25 
27 #include "SickLMS2xxMessage.hh"
28 
29 /* Macro definitions */
30 #define DEFAULT_SICK_LMS_2XX_SICK_BAUD (B9600)
31 #define DEFAULT_SICK_LMS_2XX_HOST_ADDRESS (0x80)
32 #define DEFAULT_SICK_LMS_2XX_SICK_ADDRESS (0x00)
33 #define DEFAULT_SICK_LMS_2XX_SICK_PASSWORD "SICK_LMS"
34 #define DEFAULT_SICK_LMS_2XX_SICK_MESSAGE_TIMEOUT (unsigned int)(1e6)
35 #define DEFAULT_SICK_LMS_2XX_SICK_SWITCH_MODE_TIMEOUT (unsigned int)(3e6)
36 #define DEFAULT_SICK_LMS_2XX_SICK_MEAN_VALUES_MESSAGE_TIMEOUT (unsigned int)(15e6)
37 #define DEFAULT_SICK_LMS_2XX_SICK_CONFIG_MESSAGE_TIMEOUT (unsigned int)(15e6)
38 #define DEFAULT_SICK_LMS_2XX_BYTE_INTERVAL (55)
39 #define DEFAULT_SICK_LMS_2XX_NUM_TRIES (3)
40 
41 /* Associate the namespace */
42 namespace SickToolbox {
43 
50  class SickLMS2xx : public SickLIDAR< SickLMS2xxBufferMonitor, SickLMS2xxMessage >
51  {
52 
53  public:
54 
56  static const uint16_t SICK_MAX_NUM_MEASUREMENTS = 721;
57 
64 
65  /* Supported 200 models */
67 
68  /* Supported 211 models */
76 
77  /* Supported 220 models */
79 
80  /* Supported 221 models */
89 
90  /* Supported 291 models */
94 
95  /* Any unknown model */
97 
98  };
99 
108  };
109 
119  };
120 
130  };
131 
140  };
141 
152  };
153 
164  };
165 
171  SICK_STATUS_OK = 0x00,
174  };
175 
191  };
192 
217  };
218 
224  SICK_BAUD_9600 = 0x42,
227  SICK_BAUD_500K = 0x48,
229  };
230 
232  static const uint8_t SICK_FLAG_AVAILABILITY_DEFAULT = 0x00;
233  static const uint8_t SICK_FLAG_AVAILABILITY_HIGH = 0x01;
234  static const uint8_t SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES = 0x02;
235  static const uint8_t SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT = 0x04;
236 
248  uint16_t sick_scan_angle;
253  uint8_t sick_laser_mode;
256  uint8_t sick_address;
257  uint8_t sick_variant;
259 
271  uint8_t sick_system_software_version[8];
272  uint8_t sick_prom_software_version[8];
274 
282  uint16_t sick_restart_time;
285 
297  uint16_t sick_pollution_vals[8];
298  uint16_t sick_pollution_calibration_vals[8];
299  uint16_t sick_reference_pollution_vals[4];
300  uint16_t sick_reference_pollution_calibration_vals[4];
302 
330 
346 
357  uint16_t sick_baud_rate;
360 
371  uint16_t sick_blanking;
382  uint8_t sick_restart;
403 
416  uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];
417  uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS];
418  uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS];
419  uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS];
424 
437  uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];
442 
457  uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];
458  uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS];
459  uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS];
460  uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS];
465 
480  uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];
485 
499  uint16_t sick_range_measurements[SICK_MAX_NUM_MEASUREMENTS];
500  uint16_t sick_reflect_measurements[SICK_MAX_NUM_MEASUREMENTS];
503  uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS];
504  uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS];
505  uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS];
509 
511  SickLMS2xx( const std::string sick_device_path );
512 
514  ~SickLMS2xx( );
515 
517  void Initialize( const sick_lms_2xx_baud_t desired_baud_rate, const uint32_t delay = 0 )
519 
521  void Uninitialize( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
522 
524  std::string GetSickDevicePath( ) const;
525 
527  sick_lms_2xx_type_t GetSickType( ) const throw( SickConfigException );
528 
530  double GetSickScanAngle( ) const throw( SickConfigException );
531 
533  double GetSickScanResolution( ) const throw( SickConfigException );
534 
537  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
538 
540  SickLMS2xx::sick_lms_2xx_measuring_units_t GetSickMeasuringUnits( ) const throw( SickConfigException );
541 
544  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
545 
547  sick_lms_2xx_sensitivity_t GetSickSensitivity( ) const throw( SickConfigException );
548 
551  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
552 
554  sick_lms_2xx_peak_threshold_t GetSickPeakThreshold( ) const throw( SickConfigException );;
555 
558  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
559 
561  sick_lms_2xx_measuring_mode_t GetSickMeasuringMode( ) const throw( SickConfigException );
562 
564  sick_lms_2xx_operating_mode_t GetSickOperatingMode( ) const throw( SickConfigException );
565 
567  void SetSickAvailability( const uint8_t sick_availability_flags = SICK_FLAG_AVAILABILITY_DEFAULT )
568  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
569 
571  uint8_t GetSickAvailability( ) const throw( SickConfigException );
572 
574  void SetSickVariant( const sick_lms_2xx_scan_angle_t scan_angle, const sick_lms_2xx_scan_resolution_t scan_resolution )
575  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
576 
578  void GetSickScan( unsigned int * const measurement_values,
579  unsigned int & num_measurement_values,
580  unsigned int * const sick_field_a_values = NULL,
581  unsigned int * const sick_field_b_values = NULL,
582  unsigned int * const sick_field_c_values = NULL,
583  unsigned int * const sick_telegram_index = NULL,
584  unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
585 
587  void GetSickScan( unsigned int * const range_values,
588  unsigned int * const reflect_values,
589  unsigned int & num_range_measurements,
590  unsigned int & num_reflect_measurements,
591  unsigned int * const sick_field_a_values = NULL,
592  unsigned int * const sick_field_b_values = NULL,
593  unsigned int * const sick_field_c_values = NULL,
594  unsigned int * const sick_telegram_index = NULL,
595  unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
596 
598  void GetSickScanSubrange( const uint16_t sick_subrange_start_index,
599  const uint16_t sick_subrange_stop_index,
600  unsigned int * const measurement_values,
601  unsigned int & num_measurement_values,
602  unsigned int * const sick_field_a_values = NULL,
603  unsigned int * const sick_field_b_values = NULL,
604  unsigned int * const sick_field_c_values = NULL,
605  unsigned int * const sick_telegram_index = NULL,
606  unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
607 
609  void GetSickPartialScan( unsigned int * const measurement_values,
610  unsigned int & num_measurement_values,
611  unsigned int & partial_scan_index,
612  unsigned int * const sick_field_a_values = NULL,
613  unsigned int * const sick_field_b_values = NULL,
614  unsigned int * const sick_field_c_values = NULL,
615  unsigned int * const sick_telegram_index = NULL,
616  unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
617 
619  void GetSickMeanValues( const uint8_t sick_sample_size,
620  unsigned int * const measurement_values,
621  unsigned int & num_measurement_values,
622  unsigned int * const sick_telegram_index = NULL,
623  unsigned int * const sick_real_time_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
624 
626  void GetSickMeanValuesSubrange( const uint8_t sick_sample_size,
627  const uint16_t sick_subrange_start_index,
628  const uint16_t sick_subrange_stop_index,
629  unsigned int * const measurement_values,
630  unsigned int & num_measurement_values,
631  unsigned int * const sick_telegram_index = NULL,
632  unsigned int * const sick_real_time_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
633 
635  sick_lms_2xx_status_t GetSickStatus( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
636 
638  bool IsSickLMS2xxFast( ) const throw( SickConfigException );
639 
641  void ResetSick( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
642 
644  std::string GetSickStatusAsString( ) const;
645 
647  std::string GetSickSoftwareVersionAsString( ) const;
648 
650  std::string GetSickConfigAsString( ) const;
651 
653  void PrintSickStatus( ) const;
654 
656  void PrintSickSoftwareVersion( ) const;
657 
659  void PrintSickConfig( ) const;
660 
661  /*
662  * NOTE: The following methods are given to make working with our
663  * predefined types a bit more manageable.
664  */
665 
667  static std::string SickTypeToString( const sick_lms_2xx_type_t sick_type );
668 
670  static sick_lms_2xx_scan_angle_t IntToSickScanAngle( const int scan_angle_int );
671 
673  static sick_lms_2xx_scan_resolution_t IntToSickScanResolution( const int scan_resolution_int );
674 
676  static sick_lms_2xx_scan_resolution_t DoubleToSickScanResolution( const double scan_resolution_double );
677 
679  static std::string SickBaudToString( const sick_lms_2xx_baud_t baud_rate );
680 
682  static sick_lms_2xx_baud_t IntToSickBaud( const int baud_int );
683 
685  static sick_lms_2xx_baud_t StringToSickBaud( const std::string baud_str );
686 
688  static std::string SickStatusToString( const sick_lms_2xx_status_t sick_status );
689 
692 
695 
697  static std::string SickSensitivityToString( const sick_lms_2xx_sensitivity_t sick_sensitivity );
698 
700  static std::string SickPeakThresholdToString( const sick_lms_2xx_peak_threshold_t sick_peak_threshold );
701 
703  static std::string SickMeasuringUnitsToString( const sick_lms_2xx_measuring_units_t sick_units );
704 
705  protected:
706 
709 
712 
715 
718 
721 
724 
727 
730 
733 
736 
739 
742 
745 
748 
751 
753  struct termios _old_term;
754 
756  void _setupConnection() throw( SickIOException, SickThreadException );
757  void _setupConnection(const uint32_t delay ) throw( SickIOException, SickThreadException );
758 
760  void _teardownConnection( ) throw( SickIOException );
761 
763  void _sendMessageAndGetReply( const SickLMS2xxMessage &sick_send_message,
764  SickLMS2xxMessage &sick_recv_message,
765  const unsigned int timeout_value,
766  const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException );
767 
769  void _sendMessageAndGetReply( const SickLMS2xxMessage &sick_send_message,
770  SickLMS2xxMessage &sick_recv_message,
771  const uint8_t reply_code,
772  const unsigned int timeout_value,
773  const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException );
774 
776  void _flushTerminalBuffer( ) throw ( SickThreadException );
777 
779  void _setSessionBaud( const sick_lms_2xx_baud_t baud_rate ) throw( SickIOException, SickThreadException, SickTimeoutException );
780 
782  bool _testSickBaud( const sick_lms_2xx_baud_t baud_rate ) throw( SickIOException, SickThreadException );
783 
785  void _setTerminalBaud( const sick_lms_2xx_baud_t sick_baud ) throw( SickIOException, SickThreadException );
786 
788  void _getSickType( ) throw( SickTimeoutException, SickIOException, SickThreadException );
789 
791  void _getSickConfig( ) throw( SickTimeoutException, SickIOException, SickThreadException );
792 
794  void _setSickConfig( const sick_lms_2xx_device_config_t &sick_config ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
795 
797  void _getSickStatus( ) throw( SickTimeoutException, SickIOException, SickThreadException );
798 
800  void _getSickErrors( unsigned int * const num_sick_errors = NULL,
801  uint8_t * const error_type_buffer = NULL,
802  uint8_t * const error_num_buffer = NULL ) throw( SickTimeoutException, SickIOException, SickThreadException );
803 
806  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
807 
810  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
811 
814  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
815 
818  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
819 
822  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
823 
826  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
827 
829  void _setSickOpModeMonitorStreamMeanValues( const uint8_t sample_size )
830  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
831 
833  void _setSickOpModeMonitorStreamValuesSubrange( const uint16_t subrange_start_index, const uint16_t subrange_stop_index )
834  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
835 
837  void _setSickOpModeMonitorStreamMeanValuesSubrange( const uint16_t sample_size, const uint16_t subrange_start_index, const uint16_t subrange_stop_index )
838  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
839 
841  void _switchSickOperatingMode( const uint8_t sick_mode, const uint8_t * const mode_params = NULL )
842  throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
843 
845  void _parseSickScanProfileB0( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b0_t &sick_scan_profile ) const;
846 
848  void _parseSickScanProfileB6( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b6_t &sick_scan_profile ) const;
849 
851  void _parseSickScanProfileB7( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_b7_t &sick_scan_profile ) const;
852 
854  void _parseSickScanProfileBF( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_bf_t &sick_scan_profile ) const;
855 
857  void _parseSickScanProfileC4( const uint8_t * const src_buffer, sick_lms_2xx_scan_profile_c4_t &sick_scan_profile ) const;
858 
860  void _parseSickConfigProfile( const uint8_t * const src_buffer, sick_lms_2xx_device_config_t &sick_device_config ) const;
861 
863  void _extractSickMeasurementValues( const uint8_t * const byte_sequence, const uint16_t num_measurements, uint16_t * const measured_values,
864  uint8_t * const field_a_values = NULL, uint8_t * const field_b_values = NULL, uint8_t * const field_c_values = NULL ) const;
865 
868 
870  bool _validSickMeasuringUnits( const sick_lms_2xx_measuring_units_t sick_units ) const;
871 
874 
877 
879  bool _validSickSensitivity( const sick_lms_2xx_sensitivity_t sick_sensitivity ) const;
880 
882  bool _validSickPeakThreshold( const sick_lms_2xx_peak_threshold_t sick_peak_threshold ) const;
883 
886 
888  bool _isSickLMS200( ) const;
889 
891  bool _isSickLMS211( ) const;
892 
894  bool _isSickLMS220( ) const;
895 
897  bool _isSickLMS221( ) const;
898 
900  bool _isSickLMS291( ) const;
901 
903  bool _isSickUnknown( ) const;
904 
906  sick_lms_2xx_baud_t _baudToSickBaud( const int baud_rate ) const;
907 
909  std::string _sickAvailabilityToString( const uint8_t availability_code ) const;
910 
912  std::string _sickRestartToString( const uint8_t restart_code ) const;
913 
915  std::string _sickTemporaryFieldToString( const uint8_t temp_field_code ) const;
916 
918  std::string _sickSubtractiveFieldsToString( const uint8_t subt_field_code ) const;
919 
921  std::string _sickContourFunctionToString( const uint8_t contour_function_code ) const;
922 
924  std::string _sickVariantToString( const unsigned int sick_variant ) const;
925 
926  };
927 
933 
939 
945 
951 
957 
963 
969 
975 
981 
987 
993 
994 } //namespace SickToolbox
995 
996 #endif //SICK_LMS_2XX_HH
LMS has encountered an error.
Definition: SickLMS2xx.hh:172
uint8_t sick_partial_scan_index
Indicates the start angle of the scan (This is useful for partial scans)
Definition: SickLMS2xx.hh:463
uint8_t sick_restart
Indicates the restart level of the device.
Definition: SickLMS2xx.hh:382
sick_lms_2xx_peak_threshold_t
Sick peak threshold. Only valid for Sick LMS 200/220!
Definition: SickLMS2xx.hh:158
uint8_t sick_variant
Sick variant {special,standard}.
Definition: SickLMS2xx.hh:257
bool _isSickLMS220() const
Indicates whether the Sick is an LMS 220.
Definition: SickLMS2xx.cc:4843
std::string _sickContourFunctionToString(const uint8_t contour_function_code) const
Converts Sick LMS contour function code to a corresponding string.
Definition: SickLMS2xx.cc:5164
Standard sensitivity: 30m @ 10% reflectivity.
Definition: SickLMS2xx.hh:147
void PrintSickConfig() const
Prints out the Sick LMS configurations parameters.
Definition: SickLMS2xx.cc:2000
uint16_t sick_reference_scale_1_dark_100
Receive signal amplitude in ADC incs when reference signal is switched off (Signal 1...
Definition: SickLMS2xx.hh:314
uint16_t sick_num_range_measurements
Number of range measurements.
Definition: SickLMS2xx.hh:497
uint16_t sick_current_angle
Angle used for power measurement.
Definition: SickLMS2xx.hh:319
uint8_t sick_peak_threshold
Peak threshold/black correction (This applies to Sick LMS 200/220 models, when Sick LMS 211/221/291 m...
Definition: SickLMS2xx.hh:374
SickLMS2xx(const std::string sick_device_path)
Primary constructor.
Definition: SickLMS2xx.cc:45
Low sensitivity: 20m @ 10% reflectivity.
Definition: SickLMS2xx.hh:149
uint8_t sick_contour_a_stop_angle
When contour function is active the stop angle of area to be monitored is defined (deg) ...
Definition: SickLMS2xx.hh:389
uint16_t sick_num_measurements
Number of measurements.
Definition: SickLMS2xx.hh:456
void _switchSickOperatingMode(const uint8_t sick_mode, const uint8_t *const mode_params=NULL)
Attempts to switch the operating mode of the Sick LMS 2xx.
Definition: SickLMS2xx.cc:4122
sick_lms_2xx_baud_t
Defines available Sick LMS 2xx baud rates.
Definition: SickLMS2xx.hh:223
sick_lms_2xx_scan_resolution_t
Defines the available resolution settings for the Sick LMS 2xx.
Definition: SickLMS2xx.hh:125
uint8_t sick_sample_size
Number of scans used in computing the returned mean.
Definition: SickLMS2xx.hh:481
struct termios _old_term
Definition: SickLMS2xx.hh:753
void PrintSickStatus() const
Prints ths status of the Sick LMS 2xx unit.
Definition: SickLMS2xx.cc:1986
Streams measured values of partial scan directly after measurement.
Definition: SickLMS2xx.hh:211
uint8_t sick_contour_c_negative_tolerance_band
When contour function is active the negative tolerance is defined in (cm)
Definition: SickLMS2xx.hh:397
struct SickToolbox::SickLMS2xx::sick_lms_2xx_scan_profile_bf_tag sick_lms_2xx_scan_profile_bf_t
Adopt c-style convention.
static std::string SickStatusToString(const sick_lms_2xx_status_t sick_status)
Converts the Sick LMS 2xx status code to a string.
Definition: SickLMS2xx.cc:2166
uint8_t sick_real_time_scan_index
If real-time scan indices are requested, this value is set (modulo 256)
Definition: SickLMS2xx.hh:462
void SetSickSensitivity(const sick_lms_2xx_sensitivity_t sick_sensitivity=SICK_SENSITIVITY_STANDARD)
Sets the Sick LMS sensitivity level.
Definition: SickLMS2xx.cc:440
A structure for aggregating the data that collectively defines the system software for the Sick LMS 2...
Definition: SickLMS2xx.hh:270
uint16_t sick_subrange_stop_index
Measurement subrange stop index.
Definition: SickLMS2xx.hh:478
uint8_t sick_measuring_units
Sick measuring units {cm,mm}.
Definition: SickLMS2xx.hh:255
bool _isSickLMS221() const
Indicates whether the Sick is an LMS 221.
Definition: SickLMS2xx.cc:4859
uint8_t sick_availability_level
Availability level of the Sick LMS.
Definition: SickLMS2xx.hh:376
uint8_t sick_real_time_scan_index
If real-time scan indices are requested, this value is set (modulo 256)
Definition: SickLMS2xx.hh:507
static const uint8_t SICK_FLAG_AVAILABILITY_DEFAULT
Availability unspecified.
Definition: SickLMS2xx.hh:232
bool _testSickBaud(const sick_lms_2xx_baud_t baud_rate)
Attempts to detect whether the LMS is operating at the given baud rate.
Definition: SickLMS2xx.cc:2590
uint8_t sick_single_measured_value_evaluation_mode
Multiple evaluation (min: 1, max: 125)
Definition: SickLMS2xx.hh:401
A structure for aggregating the data that collectively defines the operating status of the device...
Definition: SickLMS2xx.hh:247
std::string _sickSubtractiveFieldsToString(const uint8_t subt_field_code) const
Converts Sick LMS subtractive fields code to a corresponding string.
Definition: SickLMS2xx.cc:5146
sick_lms_2xx_baud_status_t _sick_baud_status
Definition: SickLMS2xx.hh:738
uint8_t _sick_mean_value_sample_size
Definition: SickLMS2xx.hh:744
Installation mode for writing EEPROM.
Definition: SickLMS2xx.hh:199
uint8_t sick_telegram_index
Telegram index modulo 256.
Definition: SickLMS2xx.hh:461
bool _returningRealTimeIndices() const
Definition: SickLMS2xx.hh:867
uint16_t sick_reference_target_mean_measured_vals
Reference target "mean measured values." Low byte: Current number of filtered mean measured values...
Definition: SickLMS2xx.hh:328
void _parseSickScanProfileB7(const uint8_t *const src_buffer, sick_lms_2xx_scan_profile_b7_t &sick_scan_profile) const
Parses a byte sequence into a scan profile corresponding to message B7.
Definition: SickLMS2xx.cc:4392
bool _validSickMeasuringUnits(const sick_lms_2xx_measuring_units_t sick_units) const
Indicates whether the given measuring units are valid/defined.
Definition: SickLMS2xx.cc:4784
Sick LMS 2xx returns reflectivity (echo amplitude) values instead of range measurements.
Definition: SickLMS2xx.hh:189
sick_lms_2xx_pollution_status_t _sick_pollution_status
Definition: SickLMS2xx.hh:729
Contains some simple exception classes.
uint16_t sick_scan_angle
Sick scanning angle (deg)
Definition: SickLMS2xx.hh:248
A structure for aggregating the data that collectively defines the pollution values and settings for ...
Definition: SickLMS2xx.hh:296
sick_lms_2xx_variant_t
Defines the Sick LMS 2xx variant type.
Definition: SickLMS2xx.hh:104
uint8_t sick_contour_b_start_angle
When contour function is active the start angle of area to be monitored is defined (deg) ...
Definition: SickLMS2xx.hh:393
uint8_t sick_contour_b_negative_tolerance_band
When contour function is active the negative tolerance is defined in (cm) uint8_t sick_contour_b_star...
Definition: SickLMS2xx.hh:392
sick_lms_2xx_status_t
Defines the status of the Sick LMS 2xx unit.
Definition: SickLMS2xx.hh:170
uint16_t sick_signal_amplitude_calibration_val
Calibration of the laser power.
Definition: SickLMS2xx.hh:322
uint16_t sick_angle_of_measurement
Angles used to reference target for power measurement.
Definition: SickLMS2xx.hh:321
uint8_t sick_field_evaluation_number
Number of evaluations when the field is infirnged (lies in [1,125])
Definition: SickLMS2xx.hh:342
uint16_t sick_baud_rate
Sick baud as reported by the device.
Definition: SickLMS2xx.hh:357
uint8_t sick_temporary_field
Indicates whether the temporary field is being used.
Definition: SickLMS2xx.hh:379
uint8_t sick_multiple_evaluation_offset_field_2
Offset for multiple evaluation of field set 2 (see page 105 of telegram listing)
Definition: SickLMS2xx.hh:344
void GetSickScan(unsigned int *const measurement_values, unsigned int &num_measurement_values, unsigned int *const sick_field_a_values=NULL, unsigned int *const sick_field_b_values=NULL, unsigned int *const sick_field_c_values=NULL, unsigned int *const sick_telegram_index=NULL, unsigned int *const sick_real_time_scan_index=NULL)
Returns the most recent measured values obtained by the Sick LMS 2xx.
Definition: SickLMS2xx.cc:977
uint8_t sick_contour_b_stop_angle
When contour function is active the stop angle of area to be monitored is defined (deg) ...
Definition: SickLMS2xx.hh:394
static const uint8_t SICK_FLAG_AVAILABILITY_HIGH
Highest availability (comparable to LMS types 1 to 5)
Definition: SickLMS2xx.hh:233
uint16_t sick_subrange_start_index
Measurement subrange start index.
Definition: SickLMS2xx.hh:477
std::string GetSickSoftwareVersionAsString() const
Acquire the Sick LMS&#39;s operating params as a printable string.
Definition: SickLMS2xx.cc:1909
void SetSickAvailability(const uint8_t sick_availability_flags=SICK_FLAG_AVAILABILITY_DEFAULT)
Sets the availability level of the device.
Definition: SickLMS2xx.cc:745
void Initialize(const sick_lms_2xx_baud_t desired_baud_rate, const uint32_t delay=0)
Attempts to initialize the Sick LMS 2xx and then sets communication at at the given baud rate...
Definition: SickLMS2xx.cc:98
void SetSickPeakThreshold(const sick_lms_2xx_peak_threshold_t sick_peak_threshold=SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION)
Sets the Sick LMS sensitivity level.
Definition: SickLMS2xx.cc:518
void _parseSickScanProfileBF(const uint8_t *const src_buffer, sick_lms_2xx_scan_profile_bf_t &sick_scan_profile) const
Parses a byte sequence into a scan profile corresponding to message B6.
Definition: SickLMS2xx.cc:4431
std::string _sickTemporaryFieldToString(const uint8_t temp_field_code) const
Converts Sick LMS temporary field code to a corresponding string.
Definition: SickLMS2xx.cc:5126
static std::string SickMeasuringModeToString(const sick_lms_2xx_measuring_mode_t sick_measuring_mode)
Converts the Sick measuring mode to a corresponding string.
Definition: SickLMS2xx.cc:2181
static const uint16_t SICK_MAX_NUM_MEASUREMENTS
Maximum number of measurements returned by the Sick LMS.
Definition: SickLMS2xx.hh:56
uint8_t GetSickAvailability() const
Gets the current Sick LMS 2xx availability level flags.
Definition: SickLMS2xx.cc:821
uint16_t sick_blanking
Maximum diameter of objects that are not to be detected (units cm)
Definition: SickLMS2xx.hh:371
uint16_t sick_num_reflect_measurements
Number of reflectivity measurements.
Definition: SickLMS2xx.hh:498
struct SickToolbox::SickLMS2xx::sick_lms_2xx_scan_profile_b0_tag sick_lms_2xx_scan_profile_b0_t
Adopt c-style convention.
std::string GetSickDevicePath() const
Gets the Sick LMS 2xx device path.
Definition: SickLMS2xx.cc:295
bool _validSickSensitivity(const sick_lms_2xx_sensitivity_t sick_sensitivity) const
Indicates whether the given sensitivity is defined.
Definition: SickLMS2xx.cc:4953
void SetSickMeasuringUnits(const sick_lms_2xx_measuring_units_t sick_units=SICK_MEASURING_UNITS_MM)
Sets the measurement units for the device.
Definition: SickLMS2xx.cc:351
uint8_t sick_pixel_oriented_evaluation
Pixel oriented evaluation.
Definition: SickLMS2xx.hh:400
static std::string SickOperatingModeToString(const sick_lms_2xx_operating_mode_t sick_operating_mode)
Converts the Sick operating mode to a corresponding string.
Definition: SickLMS2xx.cc:2212
uint8_t sick_telegram_index
Telegram index modulo 256.
Definition: SickLMS2xx.hh:439
uint16_t sick_peak_threshold_target_value
Target value of the peak threshold in ADC incs.
Definition: SickLMS2xx.hh:324
sick_lms_2xx_measuring_mode_t
Defines the measurment modes supported by Sick LMS 2xx.
Definition: SickLMS2xx.hh:180
uint8_t sick_contour_a_negative_tolerance_band
When contour function is active the negative tolerance is defined in (cm)
Definition: SickLMS2xx.hh:387
static sick_lms_2xx_baud_t StringToSickBaud(const std::string baud_str)
Converts string to corresponding Sick LMS baud.
Definition: SickLMS2xx.cc:2151
Streams minimum measured values for each segment in a sub-range.
Definition: SickLMS2xx.hh:213
sick_lms_2xx_baud_t _curr_session_baud
Definition: SickLMS2xx.hh:711
Streams all measured values in a scan.
Definition: SickLMS2xx.hh:205
~SickLMS2xx()
Destructor.
Definition: SickLMS2xx.cc:71
Streams mean values from a sample size of n consecutive scans.
Definition: SickLMS2xx.hh:207
void _getSickType()
Acquires the sick device type (as a string) from the unit.
Definition: SickLMS2xx.cc:2781
sick_lms_2xx_type_t GetSickType() const
Gets the Sick LMS 2xx type.
Definition: SickLMS2xx.cc:303
sick_lms_2xx_sensitivity_t
Sick sensitivities. Only valid for Sick LMS 211/221/291!
Definition: SickLMS2xx.hh:146
void _setupConnection()
Attempts to open a I/O stream using the device path given at object instantiation.
Definition: SickLMS2xx.cc:2321
uint8_t sick_multiple_evaluation_suppressed_objects
Multiple evaluation for objects less than the blanking size.
Definition: SickLMS2xx.hh:384
Scanning angle of 180 degrees.
Definition: SickLMS2xx.hh:117
No peak threshold detection, active black extension.
Definition: SickLMS2xx.hh:162
void GetSickMeanValues(const uint8_t sick_sample_size, unsigned int *const measurement_values, unsigned int &num_measurement_values, unsigned int *const sick_telegram_index=NULL, unsigned int *const sick_real_time_index=NULL)
Returns the most recent mean measured values from the Sick LMS 2xx.
Definition: SickLMS2xx.cc:1519
A structure for aggregating the data that define a scan profile obtained from reply B0 (See page 49 T...
Definition: SickLMS2xx.hh:414
uint8_t sick_subtractive_fields
Indicates whether fields A and B are subtractive.
Definition: SickLMS2xx.hh:380
Scanning angle of 100 degrees.
Definition: SickLMS2xx.hh:116
std::string _sick_device_path
Definition: SickLMS2xx.hh:708
sick_lms_2xx_sensitivity_t GetSickSensitivity() const
Gets the current Sick LMS 2xx sensitivity level.
Definition: SickLMS2xx.cc:596
Measurement range 8/80m; reflector bits in 8 levels.
Definition: SickLMS2xx.hh:182
double GetSickScanResolution() const
Gets the current angular resolution.
Definition: SickLMS2xx.cc:335
uint16_t sick_subrange_start_index
Measurement subrange start index.
Definition: SickLMS2xx.hh:454
void SetSickVariant(const sick_lms_2xx_scan_angle_t scan_angle, const sick_lms_2xx_scan_resolution_t scan_resolution)
Sets the variant of the Sick LMS 2xx (scan angle and scan resolution)
Definition: SickLMS2xx.cc:838
uint16_t sick_reference_scale_1_dark_66
Receive signal amplitude in ADC incs when reference signal is switched off (Signal 1...
Definition: SickLMS2xx.hh:316
Definition of class SickLMS2xxMessage.
uint8_t sick_measuring_units
Measured value and field value units.
Definition: SickLMS2xx.hh:378
uint8_t sick_real_time_scan_index
If real-time scan indices are requested, this value is set (modulo 256)
Definition: SickLMS2xx.hh:483
Medium sensitivity: 25m @ 10% reflectivity.
Definition: SickLMS2xx.hh:148
uint8_t sick_real_time_scan_index
If real-time scan indices are requested, this value is set (modulo 256)
Definition: SickLMS2xx.hh:440
uint16_t sick_reflect_subrange_start_index
Start index of the measured reflectivity value subrange.
Definition: SickLMS2xx.hh:501
void _extractSickMeasurementValues(const uint8_t *const byte_sequence, const uint16_t num_measurements, uint16_t *const measured_values, uint8_t *const field_a_values=NULL, uint8_t *const field_b_values=NULL, uint8_t *const field_c_values=NULL) const
Extracts the measured values (w/ flags) that were returned by the device.
Definition: SickLMS2xx.cc:4624
struct SickToolbox::SickLMS2xx::sick_lms_2xx_baud_status_tag sick_lms_2xx_baud_status_t
Adopt c-style convention.
void _setSickConfig(const sick_lms_2xx_device_config_t &sick_config)
Sets the current configuration in flash.
Definition: SickLMS2xx.cc:2957
A structure for aggregating the data that define a scan profile obtained from reply B4 (See page 79 T...
Definition: SickLMS2xx.hh:496
uint16_t sick_num_measurements
Number of measurements.
Definition: SickLMS2xx.hh:436
sick_lms_2xx_operating_mode_t GetSickOperatingMode() const
Gets the current Sick LMS 2xx operating mode.
Definition: SickLMS2xx.cc:729
Scanning angle of 90 degrees.
Definition: SickLMS2xx.hh:115
void _parseSickScanProfileB0(const uint8_t *const src_buffer, sick_lms_2xx_scan_profile_b0_t &sick_scan_profile) const
Parses a byte sequence into a scan profile corresponding to message B0.
Definition: SickLMS2xx.cc:4329
void _setTerminalBaud(const sick_lms_2xx_baud_t sick_baud)
Sets the local terminal baud rate.
Definition: SickLMS2xx.cc:2653
static std::string SickSensitivityToString(const sick_lms_2xx_sensitivity_t sick_sensitivity)
Converts Sick LMS 2xx sensitivity level to a corresponding string.
Definition: SickLMS2xx.cc:2260
struct SickToolbox::SickLMS2xx::sick_lms_2xx_operating_status_tag sick_lms_2xx_operating_status_t
Adopt c-style convention.
uint8_t sick_restart_time
Inidicates the restart time of the device.
Definition: SickLMS2xx.hh:383
void _setSickOpModeInstallation()
Sets the device to installation mode.
Definition: SickLMS2xx.cc:3502
static const uint8_t SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES
Send real-time indices.
Definition: SickLMS2xx.hh:234
uint8_t sick_contour_c_stop_angle
When contour function is active the stop angle of area to be monitored is defined (deg) ...
Definition: SickLMS2xx.hh:399
sick_lms_2xx_measuring_units_t
Defines the available Sick LMS 2xx measured value units.
Definition: SickLMS2xx.hh:136
uint16_t _sick_values_subrange_start_index
Definition: SickLMS2xx.hh:747
uint16_t sick_num_motor_revs
Sick number of motor revs.
Definition: SickLMS2xx.hh:250
bool _isSickLMS211() const
Indicates whether the Sick is an LMS 211.
Definition: SickLMS2xx.cc:4815
uint8_t sick_sample_size
Number of scans used in computing the returned mean.
Definition: SickLMS2xx.hh:438
uint16_t sick_reference_scale_2_dark_100
Receive signal amplitude in ADC incs when reference signal is switched off (Signal 2...
Definition: SickLMS2xx.hh:315
Measurement range 16m; fields A and B.
Definition: SickLMS2xx.hh:185
sick_lms_2xx_baud_t _baudToSickBaud(const int baud_rate) const
Converts a termios baud to an equivalent Sick baud.
Definition: SickLMS2xx.cc:5016
static const uint8_t SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT
Dazzle evalutation has no effect on switching outputs.
Definition: SickLMS2xx.hh:235
struct SickToolbox::SickLMS2xx::sick_lms_2xx_scan_profile_c4_tag sick_lms_2xx_scan_profile_c4_t
Adopt c-style convention.
Measurement range 32m; immediate data transmission, no flags.
Definition: SickLMS2xx.hh:188
A structure for aggregating the data that define a scan profile obtained from reply B7 (See page 63 T...
Definition: SickLMS2xx.hh:453
sick_lms_2xx_baud_t _desired_session_baud
Definition: SickLMS2xx.hh:714
static std::string SickBaudToString(const sick_lms_2xx_baud_t baud_rate)
Converts Sick LMS baud to a corresponding string.
Definition: SickLMS2xx.cc:2109
A structure for aggregating the data that collectively define the signal config and status...
Definition: SickLMS2xx.hh:313
bool _isSickLMS291() const
Indicates whether the Sick is an LMS 291.
Definition: SickLMS2xx.cc:4889
void _getSickStatus()
Acquires (and buffers) the status of the Sick LMS 2xx.
Definition: SickLMS2xx.cc:3216
A structure for aggregating the data that collectively defines the system restart config for the Sick...
Definition: SickLMS2xx.hh:281
struct SickToolbox::SickLMS2xx::sick_lms_2xx_pollution_status_tag sick_lms_2xx_pollution_status_t
Adopt c-style convention.
Diagnostic mode for testing purposes.
Definition: SickLMS2xx.hh:200
Special models (i.e. LMS211-/221-S19/-S20.
Definition: SickLMS2xx.hh:106
void _setSickOpModeMonitorStreamValuesFromPartialScan()
Sets the device to monitor mode and tells it to start sending partial scans.
Definition: SickLMS2xx.cc:3805
bool IsSickLMS2xxFast() const
Indicates whether the device is an LMS Fast.
Definition: SickLMS2xx.cc:1783
Measurement range 16m; reflector bits in 4 levels.
Definition: SickLMS2xx.hh:184
std::string _sickRestartToString(const uint8_t restart_code) const
Converts restart code to a corresponding string.
Definition: SickLMS2xx.cc:5085
static std::string SickTypeToString(const sick_lms_2xx_type_t sick_type)
Converts the Sick LMS type to a corresponding string.
Definition: SickLMS2xx.cc:2009
void _getSickConfig()
Acquires (and buffers) the current Sick LMS configuration from the device.
Definition: SickLMS2xx.cc:2899
sick_lms_2xx_scan_angle_t
Defines the scan angle for the Sick LMS 2xx.
Definition: SickLMS2xx.hh:114
bool _validSickScanAngle(const sick_lms_2xx_scan_angle_t sick_scan_angle) const
Indicates whether the given scan angle is defined.
Definition: SickLMS2xx.cc:4917
void Uninitialize()
Uninitializes the LMS by putting it in a mode where it stops streaming data, and returns it to the de...
Definition: SickLMS2xx.cc:229
sick_lms_2xx_measuring_mode_t GetSickMeasuringMode() const
Gets the current Sick LMS 2xx measuring mode.
Definition: SickLMS2xx.cc:713
uint8_t sick_permanent_baud_rate
0 - When power is switched on baud rate is 9600/1 - configured transmission rate is used ...
Definition: SickLMS2xx.hh:358
sick_lms_2xx_signal_status_t _sick_signal_status
Definition: SickLMS2xx.hh:732
uint16_t sick_dazzling_multiple_evaluation
Number of scans that take place before LMS switches the outputs (only applies to availability level 1...
Definition: SickLMS2xx.hh:373
static sick_lms_2xx_scan_angle_t IntToSickScanAngle(const int scan_angle_int)
Converts integer to corresponding Sick LMS scan angle.
Definition: SickLMS2xx.cc:2062
Streams measured values with associated flags.
Definition: SickLMS2xx.hh:210
Sends measured range values on request (i.e. when polled)
Definition: SickLMS2xx.hh:206
Sends the min measured values when object is detected.
Definition: SickLMS2xx.hh:202
sick_lms_2xx_peak_threshold_t GetSickPeakThreshold() const
Gets the current Sick LMS 2xx sensitivity level.
Definition: SickLMS2xx.cc:618
std::string GetSickStatusAsString() const
Acquire the Sick LMS&#39;s status as a printable string.
Definition: SickLMS2xx.cc:1876
struct SickToolbox::SickLMS2xx::sick_lms_2xx_scan_profile_b6_tag sick_lms_2xx_scan_profile_b6_t
Adopt c-style convention.
struct SickToolbox::SickLMS2xx::sick_lms_2xx_software_status_tag sick_lms_2xx_software_status_t
Adopt c-style convention.
std::string GetSickConfigAsString() const
Acquire the Sick LMS&#39;s config as a printable string.
Definition: SickLMS2xx.cc:1936
void _setSessionBaud(const sick_lms_2xx_baud_t baud_rate)
Sets the baud rate for the current communication session.
Definition: SickLMS2xx.cc:2530
uint8_t sick_contour_a_start_angle
When contour function is active the start angle of area to be monitored is defined (deg) ...
Definition: SickLMS2xx.hh:388
Provides an abstract parent for all Sick LIDAR devices.
Definition: SickLIDAR.hh:53
struct SickToolbox::SickLMS2xx::sick_lms_2xx_device_config_tag sick_lms_2xx_device_config_t
Adopt c-style convention.
uint16_t sick_peak_threshold_actual_value
Actual value of the peak threshold in ADC incs.
Definition: SickLMS2xx.hh:326
struct SickToolbox::SickLMS2xx::sick_lms_2xx_field_status_tag sick_lms_2xx_field_status_t
Adopt c-style convention.
uint8_t sick_contour_a_positive_tolerance_band
When contour function is active the positive tolerance is defined in (cm)
Definition: SickLMS2xx.hh:386
uint16_t sick_num_measurements
Number of measurements.
Definition: SickLMS2xx.hh:415
sick_lms_2xx_restart_status_t _sick_restart_status
Definition: SickLMS2xx.hh:726
Measurement range 32m; reflector bit in 2 levels.
Definition: SickLMS2xx.hh:186
uint16_t sick_reference_target_single_measured_vals
Reference target "single measured values." Low byte: Current number of filtered single measured value...
Definition: SickLMS2xx.hh:327
sick_lms_2xx_type_t _sick_type
Definition: SickLMS2xx.hh:717
void SetSickMeasuringMode(const sick_lms_2xx_measuring_mode_t sick_measuring_mode=SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE)
Sets the measuring mode for the device.
Definition: SickLMS2xx.cc:640
High sensitivity: 42m @ 10% reflectivity.
Definition: SickLMS2xx.hh:150
A structure for aggregating the data that collectively defines the Sick&#39;s config. ...
Definition: SickLMS2xx.hh:370
static sick_lms_2xx_scan_resolution_t DoubleToSickScanResolution(const double scan_resolution_double)
Converts double to corresponding Sick LMS scan resolution.
Definition: SickLMS2xx.cc:2100
uint8_t sick_telegram_index
Telegram index modulo 256.
Definition: SickLMS2xx.hh:420
Peak threshold detection, active black extension.
Definition: SickLMS2xx.hh:160
void _setSickOpModeMonitorRequestValues()
Sets the device to monitor mode and tells it to send values only upon request.
Definition: SickLMS2xx.cc:3621
void _setSickOpModeMonitorStreamMeanValues(const uint8_t sample_size)
Sets the device to monitor mode and tells it to send mean measured values.
Definition: SickLMS2xx.cc:3865
double GetSickScanAngle() const
Gets the current scan angle of the device.
Definition: SickLMS2xx.cc:319
uint16_t sick_signal_amplitude
Laser power in % of calibration value.
Definition: SickLMS2xx.hh:318
void _setSickOpModeMonitorStreamValues()
Sets the device to monitor mode and tells it to stream measured values.
Definition: SickLMS2xx.cc:3677
A general class for interfacing w/ SickLMS2xx2xx laser range finders.
Definition: SickLMS2xx.hh:50
Measurement range 32m; field A.
Definition: SickLMS2xx.hh:187
struct SickToolbox::SickLMS2xx::sick_lms_2xx_signal_status_tag sick_lms_2xx_signal_status_t
Adopt c-style convention.
Defines the abstract parent class for defining a Sick LIDAR device driver.
uint8_t sick_field_set_number
Active field set number.
Definition: SickLMS2xx.hh:343
bool _isSickUnknown() const
Indicates whether the Sick type is unknown.
Definition: SickLMS2xx.cc:4909
Standard: peak threshold detection, no black extension.
Definition: SickLMS2xx.hh:159
void ResetSick()
Reset the Sick LMS 2xx active field values NOTE: Considered successful if the LMS ready message is re...
Definition: SickLMS2xx.cc:1800
sick_lms_2xx_operating_mode_t
Defines the operating modes supported by Sick LMS 2xx. See page 41 of the LMS 2xx telegram manual for...
Definition: SickLMS2xx.hh:198
Defines a class for monitoring the receive buffer when interfacing w/ a Sick LMS 2xx laser range find...
uint8_t sick_telegram_index
Telegram index modulo 256.
Definition: SickLMS2xx.hh:482
void _parseSickScanProfileB6(const uint8_t *const src_buffer, sick_lms_2xx_scan_profile_b6_t &sick_scan_profile) const
Parses a byte sequence into a scan profile corresponding to message B6.
Definition: SickLMS2xx.cc:4362
Sick outputs navigation data records.
Definition: SickLMS2xx.hh:214
bool _validSickScanResolution(const sick_lms_2xx_scan_resolution_t sick_scan_resolution) const
Indicates whether the given scan resolution is defined.
Definition: SickLMS2xx.cc:4935
void GetSickPartialScan(unsigned int *const measurement_values, unsigned int &num_measurement_values, unsigned int &partial_scan_index, unsigned int *const sick_field_a_values=NULL, unsigned int *const sick_field_b_values=NULL, unsigned int *const sick_field_c_values=NULL, unsigned int *const sick_telegram_index=NULL, unsigned int *const sick_real_time_scan_index=NULL)
Returns the most recent partial scan obtained by Sick LMS 2xx.
Definition: SickLMS2xx.cc:1388
void GetSickScanSubrange(const uint16_t sick_subrange_start_index, const uint16_t sick_subrange_stop_index, unsigned int *const measurement_values, unsigned int &num_measurement_values, unsigned int *const sick_field_a_values=NULL, unsigned int *const sick_field_b_values=NULL, unsigned int *const sick_field_c_values=NULL, unsigned int *const sick_telegram_index=NULL, unsigned int *const sick_real_time_scan_index=NULL)
Returns the most recent measured values from the corresponding subrange.
Definition: SickLMS2xx.cc:1250
sick_lms_2xx_device_config_t _sick_device_config
Definition: SickLMS2xx.hh:741
uint8_t sick_telegram_index
Telegram index modulo 256.
Definition: SickLMS2xx.hh:506
uint8_t sick_multiple_evaluation
Multiple evalutation of scan data.
Definition: SickLMS2xx.hh:381
std::string _sickAvailabilityToString(const uint8_t availability_code) const
Converts given restart level to a corresponding string.
Definition: SickLMS2xx.cc:5039
uint16_t sick_reflect_subrange_stop_index
Stop index of the measured reflectivity value subrange.
Definition: SickLMS2xx.hh:502
A structure for aggregating the data that define a scan profile obtained from reply BF (See page 71 T...
Definition: SickLMS2xx.hh:476
static std::string SickPeakThresholdToString(const sick_lms_2xx_peak_threshold_t sick_peak_threshold)
Converts Sick LMS 2xx peak threshold to a corresponding string.
Definition: SickLMS2xx.cc:2282
uint16_t sick_stop_threshold_actual_value
Actual value of the stop threshold in ADC incs.
Definition: SickLMS2xx.hh:325
Encapsulates the Sick LIDAR Matlab/C++ toolbox.
Definition: SickLD.cc:44
sick_lms_2xx_operating_status_t _sick_operating_status
Definition: SickLMS2xx.hh:720
Measured values are in centimeters.
Definition: SickLMS2xx.hh:137
void _setSickOpModeMonitorStreamValuesSubrange(const uint16_t subrange_start_index, const uint16_t subrange_stop_index)
Sets the device to monitor mode and tells it to send a measured value subrange.
Definition: SickLMS2xx.cc:3936
uint8_t sick_measuring_mode
Measuring mode of the device.
Definition: SickLMS2xx.hh:377
Streams measured range from a scan and sub-range of reflectivity values.
Definition: SickLMS2xx.hh:215
SickLMS2xx::sick_lms_2xx_measuring_units_t GetSickMeasuringUnits() const
Gets the current Sick LMS 2xx measuring units.
Definition: SickLMS2xx.cc:424
A structure for aggregating the data that collectively define the baud config.
Definition: SickLMS2xx.hh:356
uint8_t sick_stop_threshold
Stop threshold in mV (This only applies to Sick LMS 200/220 models)
Definition: SickLMS2xx.hh:375
Sends min vertical distance to object when detected.
Definition: SickLMS2xx.hh:204
bool _validSickMeasuringMode(const sick_lms_2xx_measuring_mode_t sick_measuring_mode) const
Indicates whether the given measuring mode is defined.
Definition: SickLMS2xx.cc:4991
Measured values are in milimeters.
Definition: SickLMS2xx.hh:138
static sick_lms_2xx_baud_t IntToSickBaud(const int baud_int)
Converts integer to corresponding Sick LMS baud.
Definition: SickLMS2xx.cc:2130
struct SickToolbox::SickLMS2xx::sick_lms_2xx_restart_status_tag sick_lms_2xx_restart_status_t
uint16_t sick_subrange_stop_index
Measurement subrange stop index.
Definition: SickLMS2xx.hh:455
void PrintSickSoftwareVersion() const
Prints out relevant software versioning information.
Definition: SickLMS2xx.cc:1993
uint8_t sick_contour_b_positive_tolerance_band
When contour function is active the positive tolerance is defined in (cm)
Definition: SickLMS2xx.hh:391
uint8_t sick_device_status
Sick device status {ok,error}.
Definition: SickLMS2xx.hh:254
uint16_t sick_stop_threshold_target_value
Target value of the stop threshold in ADC incs.
Definition: SickLMS2xx.hh:323
uint16_t sick_reference_scale_2_dark_66
Receive signal amplitude in ADC incs when reference signal is switched off (Signal 2...
Definition: SickLMS2xx.hh:317
A structure for aggregating the data that define a scan profile obtained from reply B6 (See page 61 T...
Definition: SickLMS2xx.hh:435
Thrown instance where the driver can&#39;t read,write,drain,flush,... the buffers.
struct SickToolbox::SickLMS2xx::sick_lms_2xx_scan_profile_b7_tag sick_lms_2xx_scan_profile_b7_t
Adopt c-style convention.
void _flushTerminalBuffer()
Flushes terminal I/O buffers.
Definition: SickLMS2xx.cc:2396
uint16_t sick_scan_resolution
Sick angular resolution (1/100 deg)
Definition: SickLMS2xx.hh:249
void _teardownConnection()
Closes the data connection associated with the device.
Definition: SickLMS2xx.cc:2374
sick_lms_2xx_status_t GetSickStatus()
Acquire the Sick LMS 2xx status.
Definition: SickLMS2xx.cc:1738
static std::string SickMeasuringUnitsToString(const sick_lms_2xx_measuring_units_t sick_units)
Converts the Sick LMS measurement units to a corresponding string.
Definition: SickLMS2xx.cc:2304
bool _validSickPeakThreshold(const sick_lms_2xx_peak_threshold_t sick_peak_threshold) const
Indicates whether the given peak threshold is valid.
Definition: SickLMS2xx.cc:4972
uint8_t sick_contour_c_start_angle
When contour function is active the start angle of area to be monitored is defined (deg) ...
Definition: SickLMS2xx.hh:398
void _setSickOpModeDiagnostic()
Sets the device to diagnostic mode.
Definition: SickLMS2xx.cc:3561
uint8_t sick_partial_scan_index
Indicates the start angle of the scan (This is useful for partial scans)
Definition: SickLMS2xx.hh:422
Measurement range 8/80m; fields A,B, and C.
Definition: SickLMS2xx.hh:183
uint16_t sick_fields_b_c_restart_times
Restart times for fields B and C.
Definition: SickLMS2xx.hh:372
void _parseSickScanProfileC4(const uint8_t *const src_buffer, sick_lms_2xx_scan_profile_c4_t &sick_scan_profile) const
Parses a byte sequence into a scan profile corresponding to message C4.
Definition: SickLMS2xx.cc:4467
uint16_t sick_num_measurements
Number of measurements.
Definition: SickLMS2xx.hh:479
void _parseSickConfigProfile(const uint8_t *const src_buffer, sick_lms_2xx_device_config_t &sick_device_config) const
Parses a byte sequence into a Sick config structure.
Definition: SickLMS2xx.cc:4515
sick_lms_2xx_type_t
Defines the Sick LMS 2xx types. This enum lists all of the supported Sick LMS models.
Definition: SickLMS2xx.hh:63
A structure for aggregating the data that collectively define the signal config and status...
Definition: SickLMS2xx.hh:341
std::string _sickVariantToString(const unsigned int sick_variant) const
Converts the Sick LMS variant to a corresponding string.
Definition: SickLMS2xx.cc:5188
bool _isSickLMS200() const
Indicates whether the Sick is an LMS 200.
Definition: SickLMS2xx.cc:4799
A class to represent all messages sent to and from the Sick LMS 2xx.
Thrown when the driver detects (or the Sick reports) an invalid config.
uint8_t sick_contour_c_positive_tolerance_band
When contour function is active the positive tolerance is defined in (cm)
Definition: SickLMS2xx.hh:396
Sick LMS type 291-S14 (LMS Fast)
Definition: SickLMS2xx.hh:92
uint16_t sick_peak_threshold
Peak threshold in ADC incs for power measurement.
Definition: SickLMS2xx.hh:320
sick_lms_2xx_field_status_t _sick_field_status
Definition: SickLMS2xx.hh:735
Makes handling timeouts much easier.
void _setSickOpModeMonitorStreamRangeAndReflectivity()
Sets the device to monitor mode and tells it to stream both range and reflectivity values...
Definition: SickLMS2xx.cc:3737
uint16_t _sick_values_subrange_stop_index
Definition: SickLMS2xx.hh:750
void _sendMessageAndGetReply(const SickLMS2xxMessage &sick_send_message, SickLMS2xxMessage &sick_recv_message, const unsigned int timeout_value, const unsigned int num_tries)
Sends a message and searches for the corresponding reply.
Definition: SickLMS2xx.cc:2437
void _getSickErrors(unsigned int *const num_sick_errors=NULL, uint8_t *const error_type_buffer=NULL, uint8_t *const error_num_buffer=NULL)
Obtains any error codes from the Sick LMS.
Definition: SickLMS2xx.cc:3138
Thrown when error occurs during thread initialization, and uninitialization.
void GetSickMeanValuesSubrange(const uint8_t sick_sample_size, const uint16_t sick_subrange_start_index, const uint16_t sick_subrange_stop_index, unsigned int *const measurement_values, unsigned int &num_measurement_values, unsigned int *const sick_telegram_index=NULL, unsigned int *const sick_real_time_index=NULL)
Returns the most recent mean measured values from the specified subrange.
Definition: SickLMS2xx.cc:1633
sick_lms_2xx_software_status_t _sick_software_status
Definition: SickLMS2xx.hh:723
uint8_t sick_real_time_scan_index
If real-time scan indices are requested, this value is set (modulo 256)
Definition: SickLMS2xx.hh:421
void _setSickOpModeMonitorStreamMeanValuesSubrange(const uint16_t sample_size, const uint16_t subrange_start_index, const uint16_t subrange_stop_index)
Sets the device to monitor mode and tells it to send a mean value subrange.
Definition: SickLMS2xx.cc:4025
static sick_lms_2xx_scan_resolution_t IntToSickScanResolution(const int scan_resolution_int)
Converts integer to corresponding Sick LMS scan resolution.
Definition: SickLMS2xx.cc:2081
Measurement range 8m/80m; fields A,B and Dazzle (Default)
Definition: SickLMS2xx.hh:181


sicktoolbox
Author(s): Jason Derenick , Thomas Miller
autogenerated on Tue Sep 10 2019 03:37:34