sub20_ADC.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Robert Bosch LLC
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Robert Bosch LLC nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 //\Author Nikhil Deshpande, Robert Bosch LLC
00031 
00032 #ifndef SUB20_ADC_H_
00033 #define SUB20_ADC_H_
00034 
00035 #include "adc_sub20/sub20_ADC_meas.h"
00036 #include "adc_sub20/sub20_ADC_err.h"
00037 #include <list>
00038 #include <libsub.h> // sub20 device
00039 #include <map>
00040 
00041 
00042 //Define Sub20 ADC specifics
00043 namespace sub20_ADC_cmd {
00044         //-----------------------------------
00045         const unsigned short uSERIALNUMLENGTH   = 20;
00046         //-----------------------------------
00047         const double            dDEFAULT_VOLTREF                                = 3.3;
00048         const double            dDEFAULT_RATE_Hz                                = 10;
00049         const std::string       sDEFAULT_ADC_MUXCONFIG                          = "ADC_S0|";
00050         //-----------------------------------
00051         const unsigned short iMAXNUM_OF_CHANNELS = 16;          //Defined by the XDimax Unit's possible ADC Configurations
00052         //-----------------------------------
00053         std::map<std::string, int> adcMuxMap;
00054 
00055 }
00056 
00057 #define VCC_5V          5.0
00058 #define VCC_3V3         3.3
00059 
00060 //Define measurement output
00061 struct OneSub20_ADC_Meas {
00062   bool          bMeasAvailable; //indicates true if a valid measurement is available
00063   unsigned int  uiADCRaw[sub20_ADC_cmd::iMAXNUM_OF_CHANNELS];
00064   double        fADCVolt[sub20_ADC_cmd::iMAXNUM_OF_CHANNELS];
00065   ros::Time     dtomeas; //time tag measurement immediately in case of other delays
00066   std::string   strSerial;
00067 };
00068 
00069 class Sub20_ADC {
00070 public:
00072 
00079         Sub20_ADC(std::string, double, double);
00080 
00082 
00086         ~Sub20_ADC();
00087 
00089 
00097         void GetMeasurements( std::list<OneSub20_ADC_Meas>&, double, int *);
00098 
00099 private:
00100         // structure for Sub20 ADC configuration
00101         struct Sub20_ADC_Config {
00102                 int         sub20_ADC_TYPE[sub20_ADC_cmd::iMAXNUM_OF_CHANNELS]; // Type of Channel - 0=Single, 1=Differential, 2=1.1V/GND
00103                 int         sub20_ADC_MUX[sub20_ADC_cmd::iMAXNUM_OF_CHANNELS];  // Mux Codes for ADC Channels
00104                 int         Num_Chans;                  // Number of ADC Channels used
00105         };
00106         // structure for one Sub20 device configuration
00107         struct OneSub20Config {
00108                 std::string             strSub20Serial;
00109                 sub_handle              handle_subdev;
00110                 sub_device              subdev;
00111                 bool                    bSubDevConfigured;
00112                 Sub20_ADC_Config        sub20_ADC_Config;
00113         };
00114         std::list<OneSub20Config>       Sub20Device_list;
00115 
00116 
00117 
00118         // internal Sub20 device data
00119         sub_handle        subhndl;                                              //handle for subdevice
00120         bool              bSubDeviceOpen;                       //initialization flag
00121         bool              bSubDeviceConfigured;         //verify if subdevice is configured
00122         std::string       strSerial;                            //Serial number of SUB20 device
00123 
00125         void            get_ADC_MuxCode(std::string, int *, int *, int *);
00127         double          adc_To_Volts(int, char, int, double);
00129         void            initADC_MUX_MAP();
00130 };
00131 
00132 #endif /* SUB20_ADC_H_ */


adc_sub20
Author(s): Nikhil Deshpande (Maintained by Philip Roan)
autogenerated on Mon Oct 6 2014 10:10:25