c++/drivers/lms/sicklms-1.0/SickLMS.hh

Go to the documentation of this file.
00001 /*!
00002  * \file SickLMS.hh
00003  * \brief Definition of class SickLMS.
00004  * Code by Jason C. Derenick and Thomas H. Miller.
00005  * Contact derenick(at)lehigh(dot)edu
00006  *
00007  * The Sick LIDAR Matlab/C++ Toolbox
00008  * Copyright (c) 2008, Jason C. Derenick and Thomas H. Miller
00009  * All rights reserved.
00010  *
00011  * This software is released under a BSD Open-Source License.
00012  * See http://sicktoolbox.sourceforge.net
00013  */
00014 
00015 #ifndef SICK_LMS_HH
00016 #define SICK_LMS_HH
00017 
00018 /* Auto-generated header */
00019 #include "SickConfig.hh"
00020 
00021 /* Implementation dependencies */
00022 #include <string>
00023 #include <iostream>
00024 #include <termios.h>
00025 
00026 #include "SickConfig.hh"
00027 #include "SickLIDAR.hh"
00028 #include "SickLMSBufferMonitor.hh"
00029 #include "SickLMSMessage.hh"
00030 #include "SickException.hh"
00031 
00032 /* Define B500000 for OS X */
00033 #ifndef HAVE_LINUX_SERIAL_H
00034 #define B500000 0010005
00035 #endif
00036 
00037 /* Macro definitions */
00038 #define DEFAULT_SICK_LMS_SICK_BAUD                                       (B9600)  ///< Initial baud rate of the LMS (whatever is set in flash)
00039 #define DEFAULT_SICK_LMS_HOST_ADDRESS                                     (0x80)  ///< Client/host default serial address
00040 #define DEFAULT_SICK_LMS_SICK_ADDRESS                                     (0x00)  ///< Sick LMS default serial address
00041 #define DEFAULT_SICK_LMS_SICK_PASSWORD                                "SICK_LMS"  ///< Password for entering installation mode
00042 #define DEFAULT_SICK_LMS_SICK_MESSAGE_TIMEOUT                (unsigned int)(1e6)  ///< The max time to wait for a message reply (usecs)
00043 #define DEFAULT_SICK_LMS_SICK_SWITCH_MODE_TIMEOUT            (unsigned int)(3e6)  ///< Can take the Sick LD up to 3 seconds to reply (usecs)
00044 #define DEFAULT_SICK_LMS_SICK_MEAN_VALUES_MESSAGE_TIMEOUT   (unsigned int)(15e6)  ///< When using mean values, the Sick can sometimes take more than 10s to respond
00045 #define DEFAULT_SICK_LMS_SICK_CONFIG_MESSAGE_TIMEOUT        (unsigned int)(15e6)  ///< The sick can take some time to respond to config commands (usecs)
00046 #define DEFAULT_SICK_LMS_BYTE_INTERVAL                                      (55)  ///< Minimum time in microseconds between transmitted bytes
00047 #define DEFAULT_SICK_LMS_NUM_TRIES                                           (3)  ///< The max number of tries before giving up on a request
00048     
00049 /* Associate the namespace */
00050 namespace SickToolbox {
00051 
00052   /*!
00053    * \brief A general class for interfacing w/ SickLMS2xx laser range finders
00054    *
00055    * This class implements the basic telegram protocol for SickLMS2xx range finders.
00056    * It allows the setting of such parameters as angular resolution, fov, etc...
00057    */
00058   class SickLMS : public SickLIDAR< SickLMSBufferMonitor, SickLMSMessage >
00059   { 
00060 
00061   public:
00062     
00063     /** Define the maximum number of measurements */
00064     static const uint16_t SICK_MAX_NUM_MEASUREMENTS = 721;                          ///< Maximum number of measurements returned by the Sick LMS
00065 
00066     /*!
00067      * \enum sick_lms_type_t 
00068      * \brief Defines the Sick LMS 2xx types.
00069      * This enum lists all of the supported Sick LMS models.
00070      */
00071     enum sick_lms_type_t {
00072       
00073       /* Supported 200 models */
00074       SICK_LMS_TYPE_200_30106,                                                 ///< Sick LMS type 200-30106
00075       
00076       /* Supported 211 models */
00077       SICK_LMS_TYPE_211_30106,                                                 ///< Sick LMS type 211-30106
00078       SICK_LMS_TYPE_211_30206,                                                 ///< Sick LMS type 211-30206
00079       SICK_LMS_TYPE_211_S07,                                                   ///< Sick LMS type 211-S07
00080       SICK_LMS_TYPE_211_S14,                                                   ///< Sick LMS type 211-S14
00081       SICK_LMS_TYPE_211_S15,                                                   ///< Sick LMS type 211-S15
00082       SICK_LMS_TYPE_211_S19,                                                   ///< Sick LMS type 211-S19
00083       SICK_LMS_TYPE_211_S20,                                                   ///< Sick LMS type 211-S20
00084 
00085       /* Supported 220 models */
00086       SICK_LMS_TYPE_220_30106,                                                 ///< Sick LMS type 220-30106
00087 
00088       /* Supported 221 models */
00089       SICK_LMS_TYPE_221_30106,                                                 ///< Sick LMS type 221-30106
00090       SICK_LMS_TYPE_221_30206,                                                 ///< Sick LMS type 221-30206
00091       SICK_LMS_TYPE_221_S07,                                                   ///< Sick LMS type 221-S07
00092       SICK_LMS_TYPE_221_S14,                                                   ///< Sick LMS type 221-S14
00093       SICK_LMS_TYPE_221_S15,                                                   ///< Sick LMS type 221-S15
00094       SICK_LMS_TYPE_221_S16,                                                   ///< Sick LMS type 221-S16
00095       SICK_LMS_TYPE_221_S19,                                                   ///< Sick LMS type 221-S19
00096       SICK_LMS_TYPE_221_S20,                                                   ///< Sick LMS type 221-S20
00097 
00098       /* Supported 291 models */
00099       SICK_LMS_TYPE_291_S05,                                                   ///< Sick LMS type 291-S05
00100       SICK_LMS_TYPE_291_S14,                                                   ///< Sick LMS type 291-S14 (LMS Fast)
00101       SICK_LMS_TYPE_291_S15,                                                   ///< Sick LMS type 291-S15
00102 
00103       /* Any unknown model */
00104       SICK_LMS_TYPE_UNKNOWN = 0xFF                                             ///< Unknown sick type      
00105 
00106     };
00107     
00108     /*!
00109      * \enum sick_lms_variant_t
00110      * \brief Defines the Sick LMS 2xx variant type.
00111      */
00112     enum sick_lms_variant_t {
00113       SICK_LMS_VARIANT_2XX_TYPE_6 = 0x00,                                      ///< Standard LMS 2xx type 6 models
00114       SICK_LMS_VARIANT_SPECIAL = 0x01,                                         ///< Special models (i.e. LMS211-/221-S19/-S20
00115       SICK_LMS_VARIANT_UNKNOWN = 0xFF                                          ///< Unknown LMS variant
00116     };
00117 
00118     /*!
00119      * \enum sick_lms_scan_angle_t
00120      * \brief Defines the scan angle for the Sick LMS 2xx.
00121      */
00122     enum sick_lms_scan_angle_t {
00123       SICK_SCAN_ANGLE_90 = 90,                                                 ///< Scanning angle of 90 degrees
00124       SICK_SCAN_ANGLE_100 = 100,                                               ///< Scanning angle of 100 degrees
00125       SICK_SCAN_ANGLE_180 = 180,                                               ///< Scanning angle of 180 degrees
00126       SICK_SCAN_ANGLE_UNKNOWN = 0xFF                                           ///< Unknown scanning angle
00127     };
00128     
00129     /*!
00130      * \enum sick_lms_scan_resolution_t
00131      * \brief Defines the available resolution settings for the Sick LMS 2xx.
00132      */
00133     enum sick_lms_scan_resolution_t {
00134       SICK_SCAN_RESOLUTION_25 = 25,                                            ///< 0.25 degree angular resolution
00135       SICK_SCAN_RESOLUTION_50 = 50,                                            ///< 0.50 degree angular resolution
00136       SICK_SCAN_RESOLUTION_100 = 100,                                          ///< 1.00 degree angular resolution
00137       SICK_SCAN_RESOLUTION_UNKNOWN = 0xFF                                      ///< Unknown angular resolution
00138     };
00139 
00140     /*!
00141      * \enum sick_lms_measuring_units_t
00142      * \brief Defines the available Sick LMS 2xx measured value units.
00143      */
00144     enum sick_lms_measuring_units_t {
00145       SICK_MEASURING_UNITS_CM = 0x00,                                          ///< Measured values are in centimeters
00146       SICK_MEASURING_UNITS_MM = 0x01,                                          ///< Measured values are in milimeters
00147       SICK_MEASURING_UNITS_UNKNOWN = 0xFF                                      ///< Unknown units
00148     };
00149 
00150     /*!
00151      * \enum sick_lms_sensitivity_t
00152      * \brief Sick sensitivities. Only valid for Sick LMS 211/221/291!
00153      */
00154     enum sick_lms_sensitivity_t {
00155       SICK_SENSITIVITY_STANDARD = 0x00,                                        ///< Standard sensitivity: 30m @ 10% reflectivity
00156       SICK_SENSITIVITY_MEDIUM = 0x01,                                          ///< Medium sensitivity:   25m @ 10% reflectivity
00157       SICK_SENSITIVITY_LOW = 0x02,                                             ///< Low sensitivity:      20m @ 10% reflectivity
00158       SICK_SENSITIVITY_HIGH = 0x03,                                            ///< High sensitivity:     42m @ 10% reflectivity
00159       SICK_SENSITIVITY_UNKNOWN = 0xFF                                          ///< Sensitivity unknown
00160     };
00161 
00162     /*!
00163      * \enum sick_lms_peak_threshold_t
00164      * \brief Sick peak threshold. Only valid for Sick LMS 200/220!
00165      */
00166     enum sick_lms_peak_threshold_t {
00167       SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION = 0x00,            ///< Standard: peak threshold detection, no black extension
00168       SICK_PEAK_THRESHOLD_DETECTION_WITH_BLACK_EXTENSION = 0x01,               ///< Peak threshold detection, active black extension
00169       SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_NO_BLACK_EXTENSION = 0x02,         ///< No peak threshold detection, no black extension
00170       SICK_PEAK_THRESHOLD_NO_DETECTION_WITH_BLACK_EXTENSION = 0x03,            ///< No peak threshold detection, active black extension
00171       SICK_PEAK_THRESHOLD_UNKNOWN = 0xFF                                       ///< Peak threshold unknown
00172     };
00173 
00174     /*!
00175      * \enum sick_lms_status_t
00176      * \brief Defines the status of the Sick LMS 2xx unit.
00177      */
00178     enum sick_lms_status_t {
00179       SICK_STATUS_OK = 0x00,                                                   ///< LMS is OK
00180       SICK_STATUS_ERROR = 0x01,                                                ///< LMS has encountered an error
00181       SICK_STATUS_UNKNOWN = 0xFF                                               ///< Unknown LMS status
00182     };
00183     
00184     /*!
00185      * \enum sick_lms_measuring_mode_t
00186      * \brief Defines the measurment modes supported by Sick LMS 2xx.
00187      */
00188     enum sick_lms_measuring_mode_t { 
00189       SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE = 0x00,                                ///< Measurement range 8m/80m; fields A,B and Dazzle (Default)
00190       SICK_MS_MODE_8_OR_80_REFLECTOR = 0x01,                                   ///< Measurement range 8/80m; reflector bits in 8 levels
00191       SICK_MS_MODE_8_OR_80_FA_FB_FC = 0x02,                                    ///< Measurement range 8/80m; fields A,B, and C
00192       SICK_MS_MODE_16_REFLECTOR = 0x03,                                        ///< Measurement range 16m; reflector bits in 4 levels
00193       SICK_MS_MODE_16_FA_FB = 0x04,                                            ///< Measurement range 16m; fields A and B
00194       SICK_MS_MODE_32_REFLECTOR = 0x05,                                        ///< Measurement range 32m; reflector bit in 2 levels
00195       SICK_MS_MODE_32_FA = 0x06,                                               ///< Measurement range 32m; field A
00196       SICK_MS_MODE_32_IMMEDIATE = 0x0F,                                        ///< Measurement range 32m; immediate data transmission, no flags      
00197       SICK_MS_MODE_REFLECTIVITY = 0x3F,                                        ///< Sick LMS 2xx returns reflectivity (echo amplitude) values instead of range measurements
00198       SICK_MS_MODE_UNKNOWN = 0xFF                                              ///< Unknown range
00199     };
00200     
00201     /*!
00202      * \enum sick_lms_operating_mode_t
00203      * \brief Defines the operating modes supported by Sick LMS 2xx. 
00204      * See page 41 of the LMS 2xx telegram manual for additional descriptions of these modes.
00205      */
00206     enum sick_lms_operating_mode_t {
00207       SICK_OP_MODE_INSTALLATION = 0x00,                                        ///< Installation mode for writing EEPROM
00208       SICK_OP_MODE_DIAGNOSTIC = 0x10,                                          ///< Diagnostic mode for testing purposes
00209       SICK_OP_MODE_MONITOR_STREAM_MIN_VALUE_FOR_EACH_SEGMENT = 0x20,           ///< Streams minimum measured values for each segement
00210       SICK_OP_MODE_MONITOR_TRIGGER_MIN_VALUE_ON_OBJECT = 0x21,                 ///< Sends the min measured values when object is detected
00211       SICK_OP_MODE_MONITOR_STREAM_MIN_VERT_DIST_TO_OBJECT = 0x22,              ///< Streams min "vertical distance" to objects
00212       SICK_OP_MODE_MONITOR_TRIGGER_MIN_VERT_DIST_TO_OBJECT = 0x23,             ///< Sends min vertical distance to object when detected
00213       SICK_OP_MODE_MONITOR_STREAM_VALUES = 0x24,                               ///< Streams all measured values in a scan 
00214       SICK_OP_MODE_MONITOR_REQUEST_VALUES = 0x25,                              ///< Sends measured range values on request (i.e. when polled)
00215       SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES = 0x26,                          ///< Streams mean values from a sample size of n consecutive scans
00216       SICK_OP_MODE_MONITOR_STREAM_VALUES_SUBRANGE = 0x27,                      ///< Streams data from given subrange
00217       SICK_OP_MODE_MONITOR_STREAM_MEAN_VALUES_SUBRANGE = 0x28,                 ///< Streams mean values over requested subrange
00218       SICK_OP_MODE_MONITOR_STREAM_VALUES_WITH_FIELDS = 0x29,                   ///< Streams measured values with associated flags
00219       SICK_OP_MODE_MONITOR_STREAM_VALUES_FROM_PARTIAL_SCAN = 0x2A,             ///< Streams measured values of partial scan directly after measurement
00220       SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT_FROM_PARTIAL_SCAN = 0x2B,  ///< Streams range and intensity from n partial scans
00221       SICK_OP_MODE_MONITOR_STREAM_MIN_VALUES_FOR_EACH_SEGMENT_SUBRANGE = 0x2C, ///< Streams minimum measured values for each segment in a sub-range
00222       SICK_OP_MODE_MONITOR_NAVIGATION = 0x2E,                                  ///< Sick outputs navigation data records
00223       SICK_OP_MODE_MONITOR_STREAM_RANGE_AND_REFLECT = 0x50,                    ///< Streams measured range from a scan and sub-range of reflectivity values
00224       SICK_OP_MODE_UNKNOWN = 0xFF                                              ///< Unknown operating mode
00225     };
00226 
00227     /*!
00228      * \enum sick_lms_baud_t
00229      * \brief Defines available Sick LMS 2xx baud rates
00230      */
00231     enum sick_lms_baud_t {
00232       SICK_BAUD_9600 = 0x42,                                                   ///< 9600 baud
00233       SICK_BAUD_19200 = 0x41,                                                  ///< 19200 baud
00234       SICK_BAUD_38400 = 0x40,                                                  ///< 38400 baud
00235       SICK_BAUD_500K = 0x48,                                                   ///< 500000 baud
00236       SICK_BAUD_UNKNOWN = 0xFF                                                 ///< Unknown baud rate
00237     };
00238 
00239     /** Define Sick LMS 2xx availability levels */
00240     static const uint8_t SICK_FLAG_AVAILABILITY_DEFAULT = 0x00;                ///< Availability unspecified
00241     static const uint8_t SICK_FLAG_AVAILABILITY_HIGH = 0x01;                   ///< Highest availability (comparable to LMS types 1 to 5)
00242     static const uint8_t SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES = 0x02;      ///< Send real-time indices
00243     static const uint8_t SICK_FLAG_AVAILABILITY_DAZZLE_NO_EFFECT = 0x04;       ///< Dazzle evalutation has no effect on switching outputs
00244   
00245     /*!
00246      * \struct sick_lms_operating_status_tag
00247      * \brief A structure for aggregating the data that
00248      *        collectively defines the operating status
00249      *        of the device.
00250      */
00251     /*!
00252      * \typedef sick_lms_operating_status_t
00253      * \brief Adopt c-style convention
00254      */
00255     typedef struct sick_lms_operating_status_tag {
00256       uint16_t sick_scan_angle;                                                ///< Sick scanning angle (deg)
00257       uint16_t sick_scan_resolution;                                           ///< Sick angular resolution (1/100 deg)
00258       uint16_t sick_num_motor_revs;                                            ///< Sick number of motor revs
00259       uint8_t sick_operating_mode;                                             ///< Sick operating mode
00260       uint8_t sick_measuring_mode;                                             ///< Sick measuring mode
00261       uint8_t sick_laser_mode;                                                 ///< Sick laser is on/off
00262       uint8_t sick_device_status;                                              ///< Sick device status {ok,error}
00263       uint8_t sick_measuring_units;                                            ///< Sick measuring units {cm,mm}
00264       uint8_t sick_address;                                                    ///< Sick device address
00265       uint8_t sick_variant;                                                    ///< Sick variant {special,standard}
00266     } sick_lms_operating_status_t;
00267     
00268     /*!
00269      * \struct sick_lms_software_status_tag
00270      * \brief A structure for aggregating the data that
00271      *        collectively defines the system software
00272      *        for the Sick LMS 2xx unit.
00273      */
00274     /*!
00275      * \typedef sick_lms_software_status_t
00276      * \brief Adopt c-style convention
00277      */
00278     typedef struct sick_lms_software_status_tag {
00279       uint8_t sick_system_software_version[8];                                 ///< Sick system software version
00280       uint8_t sick_prom_software_version[8];                                   ///< Sick boot prom software version
00281     } sick_lms_software_status_t;
00282     
00283     /*!
00284      * \struct sick_lms_restart_status_tag
00285      * \brief A structure for aggregating the data that
00286      *        collectively defines the system restart
00287      *        config for the Sick LMS 2xx unit
00288      */
00289     typedef struct sick_lms_restart_status_tag {
00290       uint16_t sick_restart_time;                                              ///< Sick restart time  
00291       uint8_t sick_restart_mode;                                               ///< Sick restart mode
00292     } sick_lms_restart_status_t;
00293     
00294     /*!
00295      * \struct sick_lms_pollution_status_tag
00296      * \brief A structure for aggregating the data that
00297      *        collectively defines the pollution values
00298      *        and settings for the device
00299      */
00300     /*!
00301      * \typedef sick_lms_pollution_status_t
00302      * \brief Adopt c-style convention
00303      */
00304     typedef struct sick_lms_pollution_status_tag {
00305       uint16_t sick_pollution_vals[8];                                         ///< Calibrating the pollution channels
00306       uint16_t sick_pollution_calibration_vals[8];                             ///< Calibrating the pollution channel values
00307       uint16_t sick_reference_pollution_vals[4];                               ///< Reference pollution values
00308       uint16_t sick_reference_pollution_calibration_vals[4];                   ///< Reference pollution calibration values
00309     } sick_lms_pollution_status_t;
00310     
00311     /*!
00312      * \struct sick_lms_signal_status_tag
00313      * \brief A structure for aggregating the data that
00314      *        collectively define the signal config and
00315      *        status.
00316      */
00317     /*!
00318      * \typedef sick_lms_signal_status_t
00319      * \brief Adopt c-style convention
00320      */
00321     typedef struct sick_lms_signal_status_tag {
00322       uint16_t sick_reference_scale_1_dark_100;                                ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 1, Dark 100%)
00323       uint16_t sick_reference_scale_2_dark_100;                                ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 2, Dark 100%)
00324       uint16_t sick_reference_scale_1_dark_66;                                 ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 1, Dark 66%)
00325       uint16_t sick_reference_scale_2_dark_66;                                 ///< Receive signal amplitude in ADC incs when reference signal is switched off (Signal 2, Dark 66%)
00326       uint16_t sick_signal_amplitude;                                          ///< Laser power in % of calibration value
00327       uint16_t sick_current_angle;                                             ///< Angle used for power measurement 
00328       uint16_t sick_peak_threshold;                                            ///< Peak threshold in ADC incs for power measurement
00329       uint16_t sick_angle_of_measurement;                                      ///< Angles used to reference target for power measurement
00330       uint16_t sick_signal_amplitude_calibration_val;                          ///< Calibration of the laser power
00331       uint16_t sick_stop_threshold_target_value;                               ///< Target value of the stop threshold in ADC incs
00332       uint16_t sick_peak_threshold_target_value;                               ///< Target value of the peak threshold in ADC incs
00333       uint16_t sick_stop_threshold_actual_value;                               ///< Actual value of the stop threshold in ADC incs
00334       uint16_t sick_peak_threshold_actual_value;                               ///< Actual value of the peak threshold in ADC incs
00335       uint16_t sick_reference_target_single_measured_vals;                     ///< Reference target "single measured values." Low byte: Current number of filtered single measured values. High byte: Max num filtered single measured value since power-on. 
00336       uint16_t sick_reference_target_mean_measured_vals;                       ///< Reference target "mean measured values." Low byte: Current number of filtered mean measured values. High byte: Max num filtered mean measured value since power-on. 
00337     } sick_lms_signal_status_t;
00338     
00339     /*!
00340      * \struct sick_lms_field_status_tag
00341      * \brief A structure for aggregating the data that
00342      *        collectively define the signal config and
00343      *        status.
00344      */
00345     /*!
00346      * \typedef sick_lms_field_status_t
00347      * \brief Adopt c-style convention
00348      */
00349     typedef struct sick_lms_field_status_tag {
00350       uint8_t sick_field_evaluation_number;                                    ///< Number of evaluations when the field is infirnged (lies in [1,125])
00351       uint8_t sick_field_set_number;                                           ///< Active field set number
00352       uint8_t sick_multiple_evaluation_offset_field_2;                         ///< Offset for multiple evaluation of field set 2 (see page 105 of telegram listing)
00353     } sick_lms_field_status_t;
00354     
00355     /*!
00356      * \struct sick_lms_baud_status_tag
00357      * \brief A structure for aggregating the data that
00358      *        collectively define the baud config.
00359      */
00360     /*!
00361      * \typedef sick_lms_baud_status_t
00362      * \brief Adopt c-style convention
00363      */
00364     typedef struct sick_lms_baud_status_tag {
00365       uint16_t sick_baud_rate;                                                 ///< Sick baud as reported by the device 
00366       uint8_t sick_permanent_baud_rate;                                        ///< 0 - When power is switched on baud rate is 9600/1 - configured transmission rate is used                                   
00367     } sick_lms_baud_status_t;
00368     
00369     /*!
00370      * \struct sick_lms_device_config_tag
00371      * \brief A structure for aggregating the data that
00372      *        collectively defines the Sick's config.
00373      */
00374     /*!
00375      * \typedef sick_lms_device_config_t
00376      * \brief Adopt c-style convention
00377      */
00378     typedef struct sick_lms_device_config_tag {
00379       uint16_t sick_blanking;                                                  ///< Maximum diameter of objects that are not to be detected (units cm)                
00380       uint16_t sick_fields_b_c_restart_times;                                  ///< Restart times for fields B and C
00381       uint16_t sick_dazzling_multiple_evaluation;                              ///< Number of scans that take place before LMS switches the outputs (only applies to availability level 1)
00382       uint8_t sick_peak_threshold;                                             ///< Peak threshold/black correction (This applies to Sick LMS 200/220 models, when Sick LMS 211/221/291 models are used, this value is sensitivity)
00383       uint8_t sick_stop_threshold;                                             ///< Stop threshold in mV (This only applies to Sick LMS 200/220 models)
00384       uint8_t sick_availability_level;                                         ///< Availability level of the Sick LMS     
00385       uint8_t sick_measuring_mode;                                             ///< Measuring mode of the device 
00386       uint8_t sick_measuring_units;                                            ///< Measured value and field value units
00387       uint8_t sick_temporary_field;                                            ///< Indicates whether the temporary field is being used
00388       uint8_t sick_subtractive_fields;                                         ///< Indicates whether fields A and B are subtractive
00389       uint8_t sick_multiple_evaluation;                                        ///< Multiple evalutation of scan data
00390       uint8_t sick_restart;                                                    ///< Indicates the restart level of the device
00391       uint8_t sick_restart_time;                                               ///< Inidicates the restart time of the device
00392       uint8_t sick_multiple_evaluation_suppressed_objects;                     ///< Multiple evaluation for objects less than the blanking size
00393       uint8_t sick_contour_a_reference;                                        ///< Contour function A
00394       uint8_t sick_contour_a_positive_tolerance_band;                          ///< When contour function is active the positive tolerance is defined in (cm)
00395       uint8_t sick_contour_a_negative_tolerance_band;                          ///< When contour function is active the negative tolerance is defined in (cm)
00396       uint8_t sick_contour_a_start_angle;                                      ///< When contour function is active the start angle of area to be monitored is defined (deg)
00397       uint8_t sick_contour_a_stop_angle;                                       ///< When contour function is active the stop angle of area to be monitored is defined (deg)
00398       uint8_t sick_contour_b_reference;                                        ///< Contour function B
00399       uint8_t sick_contour_b_positive_tolerance_band;                          ///< When contour function is active the positive tolerance is defined in (cm)
00400       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_start_angle;                                       ///< When contour function is active the start angle of area to be monitored is defined (deg)
00401       uint8_t sick_contour_b_start_angle;                                      ///< When contour function is active the start angle of area to be monitored is defined (deg)
00402       uint8_t sick_contour_b_stop_angle;                                       ///< When contour function is active the stop angle of area to be monitored is defined (deg)
00403       uint8_t sick_contour_c_reference;                                        ///< Contour function C
00404       uint8_t sick_contour_c_positive_tolerance_band;                          ///< When contour function is active the positive tolerance is defined in (cm)
00405       uint8_t sick_contour_c_negative_tolerance_band;                          ///< When contour function is active the negative tolerance is defined in (cm)
00406       uint8_t sick_contour_c_start_angle;                                      ///< When contour function is active the start angle of area to be monitored is defined (deg)
00407       uint8_t sick_contour_c_stop_angle;                                       ///< When contour function is active the stop angle of area to be monitored is defined (deg)
00408       uint8_t sick_pixel_oriented_evaluation;                                  ///< Pixel oriented evaluation
00409       uint8_t sick_single_measured_value_evaluation_mode;                      ///< Multiple evaluation (min: 1, max: 125)
00410     } sick_lms_device_config_t;
00411     
00412     /*!
00413      * \struct sick_lms_scan_profile_b0_tag
00414      * \brief A structure for aggregating the data that
00415      *        define a scan profile obtained from reply
00416      *        B0 (See page 49 Telegram listing)
00417      */
00418     /*!
00419      * \typedef sick_lms_scan_profile_b0_t
00420      * \brief Adopt c-style convention
00421      */
00422     typedef struct sick_lms_scan_profile_b0_tag {
00423       uint16_t sick_num_measurements;                                          ///< Number of measurements
00424       uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];                   ///< Range/reflectivity measurement buffer
00425       uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field A bit value returned w/ range measurement
00426       uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field B but value returned w/ range measurement
00427       uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field C (or dazzle - depending upon sensor mode) value returned w/ range measurement
00428       uint8_t sick_telegram_index;                                             ///< Telegram index modulo 256
00429       uint8_t sick_real_time_scan_index;                                       ///< If real-time scan indices are requested, this value is set (modulo 256)
00430       uint8_t sick_partial_scan_index;                                         ///< Indicates the start angle of the scan (This is useful for partial scans)
00431     } sick_lms_scan_profile_b0_t;
00432     
00433     /*!
00434      * \struct sick_lms_scan_profile_b6_tag
00435      * \brief A structure for aggregating the data that
00436      *        define a scan profile obtained from reply
00437      *        B6 (See page 61 Telegram listing)
00438      */
00439     /*!
00440      * \typedef sick_lms_scan_profile_b6_t
00441      * \brief Adopt c-style convention
00442      */
00443     typedef struct sick_lms_scan_profile_b6_tag {
00444       uint16_t sick_num_measurements;                                          ///< Number of measurements
00445       uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];                   ///< Range/reflectivity measurement buffer
00446       uint8_t sick_sample_size;                                                ///< Number of scans used in computing the returned mean
00447       uint8_t sick_telegram_index;                                             ///< Telegram index modulo 256
00448       uint8_t sick_real_time_scan_index;                                       ///< If real-time scan indices are requested, this value is set (modulo 256)
00449     } sick_lms_scan_profile_b6_t;
00450     
00451     /*!
00452      * \struct sick_lms_scan_profile_b7_tag
00453      * \brief A structure for aggregating the data that
00454      *        define a scan profile obtained from reply
00455      *        B7 (See page 63 Telegram listing)
00456      */
00457     /*!
00458      * \typedef sick_lms_scan_profile_b7_t
00459      * \brief Adopt c-style convention
00460      */  
00461     typedef struct sick_lms_scan_profile_b7_tag {
00462       uint16_t sick_subrange_start_index;                                      ///< Measurement subrange start index
00463       uint16_t sick_subrange_stop_index;                                       ///< Measurement subrange stop index
00464       uint16_t sick_num_measurements;                                          ///< Number of measurements
00465       uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];                   ///< Range/reflectivity measurement buffer
00466       uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field A bit value returned w/ range measurement
00467       uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field B but value returned w/ range measurement
00468       uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field C (or dazzle - depending upon sensor mode) value returned w/ range measurement
00469       uint8_t sick_telegram_index;                                             ///< Telegram index modulo 256
00470       uint8_t sick_real_time_scan_index;                                       ///< If real-time scan indices are requested, this value is set (modulo 256)
00471       uint8_t sick_partial_scan_index;                                         ///< Indicates the start angle of the scan (This is useful for partial scans)
00472     } sick_lms_scan_profile_b7_t;
00473     
00474     /*!
00475      * \struct sick_lms_scan_profile_bf_tag
00476      * \brief A structure for aggregating the data that
00477      *        define a scan profile obtained from reply
00478      *        BF (See page 71 Telegram listing)
00479      */
00480     /*!
00481      * \typedef sick_lms_scan_profile_bf_t
00482      * \brief Adopt c-style convention
00483      */
00484     typedef struct sick_lms_scan_profile_bf_tag {
00485       uint16_t sick_subrange_start_index;                                      ///< Measurement subrange start index
00486       uint16_t sick_subrange_stop_index;                                       ///< Measurement subrange stop index
00487       uint16_t sick_num_measurements;                                          ///< Number of measurements
00488       uint16_t sick_measurements[SICK_MAX_NUM_MEASUREMENTS];                   ///< Range/reflectivity measurement buffer
00489       uint8_t sick_sample_size;                                                ///< Number of scans used in computing the returned mean
00490       uint8_t sick_telegram_index;                                             ///< Telegram index modulo 256
00491       uint8_t sick_real_time_scan_index;                                       ///< If real-time scan indices are requested, this value is set (modulo 256)
00492     } sick_lms_scan_profile_bf_t;
00493     
00494     /*!
00495      * \struct sick_lms_scan_profile_c4_tag
00496      * \brief A structure for aggregating the data that
00497      *        define a scan profile obtained from reply
00498      *        B4 (See page 79 Telegram listing)
00499      */
00500     /*!
00501      * \typedef sick_lms_scan_profile_c4_t
00502      * \brief Adopt c-style convention
00503      */
00504     typedef struct sick_lms_scan_profile_c4_tag {
00505       uint16_t sick_num_range_measurements;                                    ///< Number of range measurements
00506       uint16_t sick_num_reflect_measurements;                                  ///< Number of reflectivity measurements
00507       uint16_t sick_range_measurements[SICK_MAX_NUM_MEASUREMENTS];             ///< Range measurement buffer
00508       uint16_t sick_reflect_measurements[SICK_MAX_NUM_MEASUREMENTS];           ///< Reflect measurements buffer
00509       uint16_t sick_reflect_subrange_start_index;                              ///< Start index of the measured reflectivity value subrange
00510       uint16_t sick_reflect_subrange_stop_index;                               ///< Stop index of the measured reflectivity value subrange
00511       uint8_t sick_field_a_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field A bit value returned w/ range measurement
00512       uint8_t sick_field_b_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field B but value returned w/ range measurement
00513       uint8_t sick_field_c_values[SICK_MAX_NUM_MEASUREMENTS];                  ///< Reflects the Field C (or dazzle - depending upon sensor mode) value returned w/ range measurement
00514       uint8_t sick_telegram_index;                                             ///< Telegram index modulo 256
00515       uint8_t sick_real_time_scan_index;                                       ///< If real-time scan indices are requested, this value is set (modulo 256)
00516     } sick_lms_scan_profile_c4_t;
00517     
00518     /** Constructor */
00519     SickLMS( const std::string sick_device_path );
00520     
00521     /** Destructor */
00522     ~SickLMS( );
00523     
00524     /** Initializes the Sick */
00525     void Initialize( const sick_lms_baud_t desired_baud_rate )
00526       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00527 
00528     /** Uninitializes the Sick */
00529     void Uninitialize( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00530 
00531     /** Get the Sick LMS 2xx device type */
00532     sick_lms_type_t GetSickType( ) const throw( SickConfigException );
00533 
00534     /** Gets the scan angle currently being used by the device */
00535     double GetSickScanAngle( ) const throw( SickConfigException );
00536 
00537     /** Gets the scan resolution currently being used by the device */
00538     double GetSickScanResolution( ) const throw( SickConfigException );
00539 
00540     /** Set the measurement units of the device (in EEPROM) */
00541     void SetSickMeasuringUnits( const sick_lms_measuring_units_t sick_units = SICK_MEASURING_UNITS_MM )
00542       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00543 
00544     /** Get the current measurement units of the device */
00545     SickLMS::sick_lms_measuring_units_t GetSickMeasuringUnits( ) const throw( SickConfigException );
00546     
00547     /** Sets the sensitivity value for the device (in EEPROM). NOTE: Only applies to LMS 211/221/291 models. */
00548     void SetSickSensitivity( const sick_lms_sensitivity_t sick_sensitivity = SICK_SENSITIVITY_STANDARD )
00549       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00550 
00551     /** Get the current Sick LMS 2xx sensitivity level. NOTE: Only applies to LMS 211/221/291 models. */
00552     sick_lms_sensitivity_t GetSickSensitivity( ) const throw( SickConfigException );
00553 
00554     /** Sets the peak threshold mode for the device (in EEPROM). NOTE: Only applies to LMS 200/220 models */
00555     void SetSickPeakThreshold( const sick_lms_peak_threshold_t sick_peak_threshold = SICK_PEAK_THRESHOLD_DETECTION_WITH_NO_BLACK_EXTENSION )
00556       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00557     
00558     /** Get the current Sick LMS 2xx sensitivity level. NOTE: Only applies to LMS 211/221/291 models. */
00559     sick_lms_peak_threshold_t GetSickPeakThreshold( ) const throw( SickConfigException );;
00560     
00561     /** Sets the measuring mode for the device (in EEPROM). See page 98 of the telegram listing for more details. */
00562     void SetSickMeasuringMode( const sick_lms_measuring_mode_t sick_measuring_mode = SICK_MS_MODE_8_OR_80_FA_FB_DAZZLE )
00563       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00564 
00565     /** Get the current Sick LMS 2xx measuring mode */
00566     sick_lms_measuring_mode_t GetSickMeasuringMode( ) const throw( SickConfigException );
00567 
00568     /** Get the current Sick LMS 2xx operating mode */
00569     sick_lms_operating_mode_t GetSickOperatingMode( ) const throw( SickConfigException );
00570     
00571     /** Sets the availability of the device (in EEPROM). See page 98 of the telegram listing for more details. */
00572     void SetSickAvailability( const uint8_t sick_availability_flags = SICK_FLAG_AVAILABILITY_DEFAULT )
00573       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00574 
00575     /** Gets the current availability flags for the device */
00576     uint8_t GetSickAvailability( ) const throw( SickConfigException );
00577     
00578     /** Sets the variant type for the device (in EEPROM) */
00579     void SetSickVariant( const sick_lms_scan_angle_t scan_angle, const sick_lms_scan_resolution_t scan_resolution )
00580       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00581 
00582     /** Gets measurement data from the Sick. NOTE: Data can be either range or reflectivity given the Sick mode. */
00583     void GetSickScan( unsigned int * const measurement_values,
00584                       unsigned int & num_measurement_values,
00585                       unsigned int * const sick_field_a_values = NULL,
00586                       unsigned int * const sick_field_b_values = NULL,
00587                       unsigned int * const sick_field_c_values = NULL,
00588                       unsigned int * const sick_telegram_index = NULL,
00589                       unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00590 
00591     /** Gets range and reflectivity data from the Sick. NOTE: This only applies to Sick LMS 211/221/291-S14! */
00592     void GetSickScan( unsigned int * const range_values,
00593                       unsigned int * const reflect_values,
00594                       unsigned int & num_range_measurements,
00595                       unsigned int & num_reflect_measurements,
00596                       unsigned int * const sick_field_a_values = NULL,
00597                       unsigned int * const sick_field_b_values = NULL,
00598                       unsigned int * const sick_field_c_values = NULL,
00599                       unsigned int * const sick_telegram_index = NULL,
00600                       unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00601 
00602     /** Gets measurement data from the Sick. NOTE: Data can be either range or reflectivity given the Sick mode. */
00603     void GetSickScanSubrange( const uint16_t sick_subrange_start_index,
00604                               const uint16_t sick_subrange_stop_index,
00605                               unsigned int * const measurement_values,
00606                               unsigned int & num_measurement_values,
00607                               unsigned int * const sick_field_a_values = NULL,
00608                               unsigned int * const sick_field_b_values = NULL,
00609                               unsigned int * const sick_field_c_values = NULL,
00610                               unsigned int * const sick_telegram_index = NULL,
00611                               unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00612     
00613     /** Gets partial scan measurements from the Sick LMS 2xx. NOTE: Data can be either range or reflectivity depending upon the given Sick mode. */
00614     void GetSickPartialScan( unsigned int * const measurement_values,
00615                              unsigned int & num_measurement_values,
00616                              unsigned int & partial_scan_index,
00617                              unsigned int * const sick_field_a_values = NULL,
00618                              unsigned int * const sick_field_b_values = NULL,
00619                              unsigned int * const sick_field_c_values = NULL,
00620                              unsigned int * const sick_telegram_index = NULL,
00621                              unsigned int * const sick_real_time_scan_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00622 
00623     /** Gets mean measured values from the Sick LMS */
00624     void GetSickMeanValues( const uint8_t sick_sample_size,
00625                             unsigned int * const measurement_values,
00626                             unsigned int & num_measurement_values,
00627                             unsigned int * const sick_telegram_index = NULL,
00628                             unsigned int * const sick_real_time_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00629 
00630     /** Gets mean measured values from the Sick LMS */
00631     void GetSickMeanValuesSubrange( const uint8_t sick_sample_size,
00632                                     const uint16_t sick_subrange_start_index,
00633                                     const uint16_t sick_subrange_stop_index,
00634                                     unsigned int * const measurement_values,
00635                                     unsigned int & num_measurement_values,
00636                                     unsigned int * const sick_telegram_index = NULL,
00637                                     unsigned int * const sick_real_time_index = NULL ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00638 
00639     /** Acquire the Sick LMS status */
00640     sick_lms_status_t GetSickStatus( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00641 
00642     /** Indicates whether the Sick is an LMS Fast */
00643     bool IsSickLMSFast( ) const throw( SickConfigException );
00644     
00645     /** Resets Sick LMS field values */
00646     void ResetSick( ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00647     
00648     /** Get Sick status as a string */
00649     std::string GetSickStatusAsString( ) const;
00650     
00651     /** Get Sick software info as a string */
00652     std::string GetSickSoftwareVersionAsString( ) const;
00653     
00654     /** Get Sick config as a string */
00655     std::string GetSickConfigAsString( ) const;
00656     
00657     /** Print the Sick LMS status */
00658     void PrintSickStatus( ) const;
00659 
00660     /** Print the Sick LMS software versions */
00661     void PrintSickSoftwareVersion( ) const;
00662 
00663     /** Print the Sick LMS configuration */
00664     void PrintSickConfig( ) const;
00665 
00666     /*
00667      * NOTE: The following methods are given to make working with our
00668      *       predefined types a bit more manageable.
00669      */
00670 
00671     /** Converts the LMS's type to a corresponding string */
00672     static std::string SickTypeToString( const sick_lms_type_t sick_type );
00673 
00674     /** A utility function for converting integers to lms_sick_scan_angle_t */
00675     static sick_lms_scan_angle_t IntToSickScanAngle( const int scan_angle_int );
00676 
00677     /** A utility function for converting ints to lms_sick_scan_resolution_t */
00678     static sick_lms_scan_resolution_t IntToSickScanResolution( const int scan_resolution_int );
00679     
00680     /** A utility function for converting doubles to lms_sick_scan_resolution_t */
00681     static sick_lms_scan_resolution_t DoubleToSickScanResolution( const double scan_resolution_double );
00682     
00683     /** Converts the given bad, returns a string representing that baud rate. */
00684     static std::string SickBaudToString( const sick_lms_baud_t baud_rate );
00685 
00686     /** A utility function for converting integers to lms_baud_t */
00687     static sick_lms_baud_t IntToSickBaud( const int baud_int );
00688     
00689     /** A utility function for converting baud strings to lms_baud_t */
00690     static sick_lms_baud_t StringToSickBaud( const std::string baud_str );
00691 
00692     /** Converts the LMS's status to a corresponding string */
00693     static std::string SickStatusToString( const sick_lms_status_t sick_status );
00694     
00695     /** Converts the LMS's measuring mode to a corresponding string */
00696     static std::string SickMeasuringModeToString( const sick_lms_measuring_mode_t sick_measuring_mode );
00697 
00698     /** Converts the LMS's measuring mode to a corresponding string */
00699     static std::string SickOperatingModeToString( const sick_lms_operating_mode_t sick_operating_mode );
00700     
00701     /** Converts the LMS's sensitivity to string */
00702     static std::string SickSensitivityToString( const sick_lms_sensitivity_t sick_sensitivity );
00703 
00704     /** Converts the LMS's peak threshold to string */
00705     static std::string SickPeakThresholdToString( const sick_lms_peak_threshold_t sick_peak_threshold );
00706     
00707     /** Converts the LMS's measuring units to a corresponding string */
00708     static std::string SickMeasuringUnitsToString( const sick_lms_measuring_units_t sick_units );    
00709 
00710   protected:
00711 
00712     /** A path to the device at which the sick can be accessed. */
00713     std::string _sick_device_path;
00714 
00715     /** The baud rate at which to communicate with the Sick */
00716     sick_lms_baud_t _curr_session_baud;
00717 
00718     /** The desired baud rate for communicating w/ the Sick */
00719     sick_lms_baud_t _desired_session_baud;
00720     
00721     /** A string representing the type of device */
00722     sick_lms_type_t _sick_type;
00723 
00724     /** The operating parameters of the device */
00725     sick_lms_operating_status_t _sick_operating_status;
00726 
00727     /** The current software version being run on the device */
00728     sick_lms_software_status_t _sick_software_status;
00729 
00730     /** The restart configuration of the device */
00731     sick_lms_restart_status_t _sick_restart_status;
00732 
00733     /** The pollution measurement status */
00734     sick_lms_pollution_status_t _sick_pollution_status;
00735 
00736     /** The signal status of the device */
00737     sick_lms_signal_status_t _sick_signal_status;
00738 
00739     /** The field configuration for the device */
00740     sick_lms_field_status_t _sick_field_status;
00741 
00742     /** The baud configuration of the device */
00743     sick_lms_baud_status_t _sick_baud_status;
00744 
00745     /** The device configuration for the Sick */
00746     sick_lms_device_config_t _sick_device_config;
00747 
00748     /** Used when the device is streaming mean values */
00749     uint8_t _sick_mean_value_sample_size;
00750 
00751     /** Used when the device is streaming a scan subrange */
00752     uint16_t _sick_values_subrange_start_index;
00753 
00754     /** Used when the device is streaming a scan subrange */
00755     uint16_t _sick_values_subrange_stop_index;
00756     
00757     /** Stores information about the original terminal settings */
00758     struct termios _old_term;
00759 
00760     /** Opens the terminal for serial communication. */
00761     void _setupConnection( ) throw( SickIOException, SickThreadException );
00762 
00763     /** Closes the serial communication terminal. */
00764     void _teardownConnection( ) throw( SickIOException );
00765 
00766     /** Sends a message to the LMS and get the expected reply using th 0x80 rule.   @todo Check difference in comments? */
00767     void _sendMessageAndGetReply( const SickLMSMessage &sick_send_message,
00768                                   SickLMSMessage &sick_recv_message,
00769                                   const unsigned int timeout_value,
00770                                   const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException ); 
00771 
00772     /** Sends a message to the LMS and get the expected reply using th 0x80 rule. @todo Check difference in comments? */
00773     void _sendMessageAndGetReply( const SickLMSMessage &sick_send_message,
00774                                   SickLMSMessage &sick_recv_message,
00775                                   const uint8_t reply_code,
00776                                   const unsigned int timeout_value,
00777                                   const unsigned int num_tries ) throw( SickIOException, SickThreadException, SickTimeoutException ); 
00778     
00779     /** Flushes the terminal I/O buffers */
00780     void _flushTerminalBuffer( ) throw ( SickThreadException );
00781     
00782     /** Sets the baud rate for communication with the LMS. */
00783     void _setSessionBaud( const sick_lms_baud_t baud_rate ) throw( SickIOException, SickThreadException, SickTimeoutException );
00784 
00785     /** Tests communication wit the LMS at a particular baud rate. */
00786     bool _testSickBaud( const sick_lms_baud_t baud_rate ) throw( SickIOException, SickThreadException );
00787 
00788     /** Changes the terminal's baud rate. */
00789     void _setTerminalBaud( const sick_lms_baud_t sick_baud ) throw( SickIOException, SickThreadException );
00790 
00791     /** Gets the type of Sick LMS */
00792     void _getSickType( ) throw( SickTimeoutException, SickIOException, SickThreadException );
00793 
00794     /** Gets the current Sick configuration settings */
00795     void _getSickConfig( ) throw( SickTimeoutException, SickIOException, SickThreadException );
00796 
00797     /** Sets the Sick configuration in flash */
00798     void _setSickConfig( const sick_lms_device_config_t &sick_config ) throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException );
00799     
00800     /** Gets the status of the LMS */
00801     void _getSickStatus( ) throw( SickTimeoutException, SickIOException, SickThreadException );
00802 
00803     /** Gets the error status of the Sick LMS */
00804     void _getSickErrors( unsigned int * const num_sick_errors = NULL,
00805                          uint8_t * const error_type_buffer = NULL,
00806                          uint8_t * const error_num_buffer = NULL ) throw( SickTimeoutException, SickIOException, SickThreadException );
00807 
00808     /** Switch Sick LMS to installation mode */
00809     void _setSickOpModeInstallation( )
00810       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00811 
00812     /** Switch Sick LMS to diagnostic mode */
00813     void _setSickOpModeDiagnostic( )
00814       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00815 
00816     /** Switch Sick LMS to monitor mode (request range data) */
00817     void _setSickOpModeMonitorRequestValues( )
00818       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00819 
00820     /** Switch Sick LMS to monitor mode (stream range) */
00821     void _setSickOpModeMonitorStreamValues( )
00822       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00823 
00824     /** Switch Sick LMS to monitor mode (stream range and reflectivity) */
00825     void _setSickOpModeMonitorStreamRangeAndReflectivity( )
00826       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00827 
00828     /** Switch Sick LMS to monitor mode (stream range from a partial scan) */
00829     void _setSickOpModeMonitorStreamValuesFromPartialScan( )
00830       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00831 
00832     /** Switch Sick LMS to monitor mode (stream mean measured values) */
00833     void _setSickOpModeMonitorStreamMeanValues( const uint8_t sample_size )
00834       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00835 
00836     /** Switch Sick LMS to monitor mode (stream mean measured values) */
00837     void _setSickOpModeMonitorStreamValuesSubrange( const uint16_t subrange_start_index, const uint16_t subrange_stop_index )
00838       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00839 
00840     /** Switch Sick LMS to monitor mode (stream mean measured values subrange) */
00841     void _setSickOpModeMonitorStreamMeanValuesSubrange( const uint16_t sample_size, const uint16_t subrange_start_index, const uint16_t subrange_stop_index )
00842       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00843     
00844     /** Switches the operating mode of the LMS. */
00845     void _switchSickOperatingMode( const uint8_t sick_mode, const uint8_t * const mode_params = NULL )
00846       throw( SickConfigException, SickTimeoutException, SickIOException, SickThreadException);
00847     
00848     /** Parses the scan profile returned w/ message B0 */
00849     void _parseSickScanProfileB0( const uint8_t * const src_buffer, sick_lms_scan_profile_b0_t &sick_scan_profile ) const;
00850 
00851     /** Parses the scan profile returned w/ message B6 */
00852     void _parseSickScanProfileB6( const uint8_t * const src_buffer, sick_lms_scan_profile_b6_t &sick_scan_profile ) const;
00853 
00854     /** Parses the scan profile returned w/ message B6 */
00855     void _parseSickScanProfileB7( const uint8_t * const src_buffer, sick_lms_scan_profile_b7_t &sick_scan_profile ) const;
00856 
00857     /** Parses the scan profile returned w/ message BF */
00858     void _parseSickScanProfileBF( const uint8_t * const src_buffer, sick_lms_scan_profile_bf_t &sick_scan_profile ) const;
00859     
00860     /** Parses the scan profile returned w/ message C4 */
00861     void _parseSickScanProfileC4( const uint8_t * const src_buffer, sick_lms_scan_profile_c4_t &sick_scan_profile ) const;
00862 
00863     /** A function for parsing a byte sequence into a device config structure */
00864     void _parseSickConfigProfile( const uint8_t * const src_buffer, sick_lms_device_config_t &sick_device_config ) const;
00865 
00866     /** Acquires the bit mask to extract the field bit values returned with each range measurement */
00867     void _extractSickMeasurementValues( const uint8_t * const byte_sequence, const uint16_t num_measurements, uint16_t * const measured_values,
00868                                         uint8_t * const field_a_values = NULL, uint8_t * const field_b_values = NULL, uint8_t * const field_c_values = NULL ) const;
00869     
00870     /** Tells whether the device is returning real-time indices */
00871     bool _returningRealTimeIndices( ) const { return _sick_device_config.sick_availability_level & SICK_FLAG_AVAILABILITY_REAL_TIME_INDICES; }
00872 
00873     /** Indicates whether the given unit value is defined */
00874     bool _validSickMeasuringUnits( const sick_lms_measuring_units_t sick_units ) const;
00875 
00876     /** Indicates whether the given scan angle is defined */
00877     bool _validSickScanAngle( const sick_lms_scan_angle_t sick_scan_angle ) const;
00878 
00879     /** Indicates whether the given scan resolution is defined */
00880     bool _validSickScanResolution( const sick_lms_scan_resolution_t sick_scan_resolution ) const;
00881 
00882     /** Indicates whether the given sensitivity is defined */
00883     bool _validSickSensitivity( const sick_lms_sensitivity_t sick_sensitivity ) const;
00884 
00885     /** Indicates whether the given peak threshold is defined */
00886     bool _validSickPeakThreshold( const sick_lms_peak_threshold_t sick_peak_threshold ) const;
00887     
00888     /** Indicates whether the given sensitivity is defined */
00889     bool _validSickMeasuringMode( const sick_lms_measuring_mode_t sick_measuring_mode ) const;
00890 
00891     /** Indicates whether the Sick LMS is type 200 */
00892     bool _isSickLMS200( ) const;
00893     
00894     /** Indicates whether the Sick LMS is type 211 */
00895     bool _isSickLMS211( ) const;
00896     
00897     /** Indicates whether the Sick LMS is type 220 */
00898     bool _isSickLMS220( ) const;
00899     
00900     /** Indicates whether the Sick LMS is type 221 */
00901     bool _isSickLMS221( ) const;
00902     
00903     /** Indicates whether the Sick LMS is type 291 */
00904     bool _isSickLMS291( ) const;
00905 
00906     /** Indicates whether the Sick LMS type is unknown */
00907     bool _isSickUnknown( ) const;
00908     
00909     /** Given a baud rate as an integer, gets a LMS baud rate command. */
00910     sick_lms_baud_t _baudToSickBaud( const int baud_rate ) const;
00911 
00912     /** Given a bytecode representing Sick LMS availability, returns a corresponding string */
00913     std::string _sickAvailabilityToString( const uint8_t availability_code ) const;
00914 
00915     /** Given a bytecode representing Sick LMS restart mode, returns a corresponding string */
00916     std::string _sickRestartToString( const uint8_t restart_code ) const;
00917     
00918     /** Converts the LMS's temporary field value to a string */
00919     std::string _sickTemporaryFieldToString( const uint8_t temp_field_code ) const;
00920 
00921     /** Converts the LMS's subtractive field value to a string */
00922     std::string _sickSubtractiveFieldsToString( const uint8_t subt_field_code ) const;
00923 
00924     /** Converts the LMS's contour function status code to a string */
00925     std::string _sickContourFunctionToString( const uint8_t contour_function_code ) const;
00926     
00927     /** Converts the LMS's variant to a corresponding string */
00928     std::string _sickVariantToString( const unsigned int sick_variant ) const;
00929 
00930   };
00931 
00932   /*!
00933    * \typedef sick_lms_type_t
00934    * \brief Makes working w/ SickLMS::sick_lms_type_t a bit easier
00935    */
00936   typedef SickLMS::sick_lms_type_t sick_lms_type_t;
00937 
00938   /*!
00939    * \typedef sick_lms_variant_t
00940    * \brief Makes working w/ SickLMS::sick_lms_variant_t a bit easier
00941    */
00942   typedef SickLMS::sick_lms_variant_t sick_lms_variant_t;
00943 
00944   /*!
00945    * \typedef sick_lms_scan_angle_t
00946    * \brief Makes working w/ SickLMS::sick_lms_scan_angle_t a bit easier
00947    */
00948   typedef SickLMS::sick_lms_scan_angle_t sick_lms_scan_angle_t;
00949 
00950   /*!
00951    * \typedef sick_lms_scan_resolution_t
00952    * \brief Makes working w/ SickLMS::sick_lms_scan_resolution_t a bit easier
00953    */
00954   typedef SickLMS::sick_lms_scan_resolution_t sick_lms_scan_resolution_t;
00955 
00956   /*!
00957    * \typedef sick_lms_measuring_units_t
00958    * \brief Makes working w/ SickLMS::sick_lms_measuring_units_t a bit easier
00959    */
00960   typedef SickLMS::sick_lms_measuring_units_t sick_lms_measuring_units_t;
00961 
00962   /*!
00963    * \typedef sick_lms_sensitivity_t
00964    * \brief Makes working w/ SickLMS::sick_lms_sensitivity_t a bit easier
00965    */
00966   typedef SickLMS::sick_lms_sensitivity_t sick_lms_sensitivity_t;
00967 
00968   /*!
00969    * \typedef sick_lms_peak_threshold_t
00970    * \brief Makes working w/ SickLMS::sick_lms_peak_threshold_t a bit easier
00971    */
00972   typedef SickLMS::sick_lms_peak_threshold_t sick_lms_peak_threshold_t;
00973   
00974   /*!
00975    * \typedef sick_lms_status_t
00976    * \brief Makes working w/ SickLMS::sick_lms_status_t a bit easier
00977    */
00978   typedef SickLMS::sick_lms_status_t sick_lms_status_t;
00979 
00980   /*!
00981    * \typedef sick_lms_measuring_mode_t
00982    * \brief Makes working w/ SickLMS::sick_lms_measuring_mode_t a bit easier
00983    */
00984   typedef SickLMS::sick_lms_measuring_mode_t sick_lms_measuring_mode_t;
00985 
00986   /*!
00987    * \typedef sick_lms_operating_mode_t
00988    * \brief Makes working w/ SickLMS::sick_lms_operating_mode_t a bit easier
00989    */
00990   typedef SickLMS::sick_lms_operating_mode_t sick_lms_operating_mode_t;
00991 
00992   /*!
00993    * \typedef sick_lms_baud_t
00994    * \brief Makes working w/ SickLMS::sick_lms_baud_t a bit easier
00995    */
00996   typedef SickLMS::sick_lms_baud_t sick_lms_baud_t;
00997   
00998 } //namespace SickToolbox
00999   
01000 #endif //SICK_LMS_HH

Generated on Thu Mar 20 09:41:42 2008 for sicktoolbox-1.0 by  doxygen 1.5.1