bma180.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 /*********************************************************************
00031  *
00032  * Disclaimer
00033  *
00034  * This source code is not officially released or supported by Bosch Sensortec.
00035  * Please contact the listed authors with bugs or other modifications.
00036  * If you would like the official Bosch Sensortec drivers, please contact:
00037  * contact@bosch-sensortec.com
00038  *
00039  *********************************************************************/
00040 
00041 /*
00042  * bma180.h
00043  *
00044  *  Created on: Jul 26, 2011
00045  *      Author: Lucas Marti, Robert Bosch LLC |
00046  *      Editor: Nikhil Deshpande, Robert Bosch LLC |
00047  */
00048 
00049 #ifndef BMA180_H_
00050 #define BMA180_H_
00051 
00052 #include "bma180/bma180meas.h"
00053 #include "bma180/bma180err.h"
00054 #include "bma180/bma180_calibrate.h"
00055 #include <list>
00056 #include <libsub.h> // sub20 device
00057 
00058 //Define BMA180 specifics
00059 namespace bma180_cmd {
00060   const char chFLAG_R             = {0x80};
00061   //Define BMA180 commands
00062   const char    chADR_ACCLXYZ        = {0x02};  //read accel data
00063   const char    chADR_VER            = {0x00};  //read version data
00064   const char    chADR_STATREG1       = {0x09};
00065   const char    chADR_STATREG2       = {0x0A};
00066   const char    chADR_STATREG3       = {0x0B};
00067   const char    chADR_STATREG4       = {0x0C};
00068   const char    chADR_CTRLREG0       = {0x0D};
00069   const char    chADR_CTRLREG1       = {0x0E};
00070   const char    chADR_CTRLREG2       = {0x0F};
00071   const char    chADR_SOFTRESET      = {0x10};
00072   const char    chADR_EE_OFFSET_Z    = {0x5A};  // |
00073   const char    chADR_EE_OFFSET_Y    = {0x59};  // |
00074   const char    chADR_EE_OFFSET_X    = {0x58};  // |-> THIS IS THE EEPROM
00075   const char    chADR_EE_OFFSET_T    = {0x57};  // |
00076   const char    chADR_EE_OFFSET_LSB2 = {0x56};  // |
00077   const char    chADR_EE_OFFSET_LSB1 = {0x55};  // |
00078   const char    chADR_OFFSET_Z       = {0x3A};
00079   const char    chADR_OFFSET_Y       = {0x39};
00080   const char    chADR_OFFSET_X       = {0x38};
00081   const char    chADR_OFFSET_T       = {0x37};
00082   const char    chADR_OFFSET_LSB2    = {0x36};
00083   const char    chADR_OFFSET_LSB1    = {0x35};
00084   const char    chADR_EE_GAIN_Z      = {0x54};
00085   //-----------------------------------
00086   const char    chADR_BWTCS          = {0x20};
00087   const char    chADR_RANGE          = {0x35};
00088   //-----------------------------------
00089   const double  dFULLRANGELOOKUP[] = {1.0, 1.5, 2.0, 3.0, 4.0, 8.0, 16.0};
00090   const char    chCMD_FULLSCALE_G[]= {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06};
00091   //-----------------------------------
00092   const double  dBWLOOKUP[]       = {10, 20, 40, 75, 150, 300, 600, 1200};
00093   const char    chCMD_BANDWIDTH_HZ[]= {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07};
00094   //-----------------------------------
00095   const char    chCMD_SOFTRESET         = {0xB6};
00096   const char    chCMD_SET_EEW           = {0x01};
00097   //-----------------------------------
00098   enum eSensorType {eACCEL, eTEMP, eBIAS_X, eBIAS_Y, eBIAS_Z};
00099   //-----------------------------------
00100   const unsigned short iMAXNUM_OF_SENSORS = 5;          //Defined by the Xdimax Unit (which supports 5 sensors per box)
00101   //-----------------------------------
00102   const double  dDEFAULT_MAXACC_g               = 16;
00103   const std::string     sSUB20SERIAL("0651");
00104   const double  dDEFAULT_BANDWIDTH_Hz           = 300;
00105   const double  dDEFAULT_RATE_Hz                = 500;
00106   const bool    bDEFAULT_CALIBRATE              = false;
00107   const double  dCALIB_ACCURACY                 = 0.05;
00108   //-----------------------------------
00109   const unsigned short uSERIALNUMLENGTH = 20;
00110   //-----------------------------------
00111   const short   iDEFAULT_CALIBCHIPSELECT= 0;            //this is out of range and ensures that no calibration is executed in case of error
00112 }
00113 
00114 //Define measurement output
00115 struct OneBma180Meas {
00116   bool          bMeasAvailable; //indicates true if a valid measurement is available
00117   int           iNumAccels;
00118   double        dAccX[bma180_cmd::iMAXNUM_OF_SENSORS];
00119   double        dAccY[bma180_cmd::iMAXNUM_OF_SENSORS];
00120   double        dAccZ[bma180_cmd::iMAXNUM_OF_SENSORS];
00121   double        dTemp;
00122   ros::Time     dtomeas; //time tag measurement immediately in case of other delays
00123   std::string   strSerial;
00124   int           iChipSelect[bma180_cmd::iMAXNUM_OF_SENSORS];
00125 };
00126 
00127 
00129 
00135 class Bma180 {
00136   public:
00138 
00150         Bma180(double, double, bool, double, std::string);
00151 
00153 
00157         ~Bma180();
00158 
00160 
00170         void GetMeasurements( std::list<OneBma180Meas>& );
00171 
00172   private:
00173         // structure for one bma180 configuration
00174     struct OneBma180Config {
00175       double          dFullScaleRange;
00176       double          dSensorBandwidth;
00177       bool            bConfigured;
00178       unsigned short  uiBiasImageX;
00179       unsigned short  uiBiasImageY;
00180       unsigned short  uiBiasImageZ;
00181       double          iNumOfCalibMeas;
00182     };
00183         // structure for one Sub20 device configuration
00184     struct OneSub20Config {
00185       std::string     strSub20Serial;
00186       sub_handle      handle_subdev;
00187       sub_device      subdev;
00188       bool            bSubSPIConfigured;
00189       OneBma180Config Bma180Cluster[bma180_cmd::iMAXNUM_OF_SENSORS];
00190     };
00191     std::list<OneSub20Config>   Sub20Device_list;
00192 
00193     // internal calibration flags
00194     bool              bExecuteCalibration;
00195     bool              bCalibrationCompleted;
00196     bma180_calibrate  calib_bma180;
00197 
00198     // internal selected accelerometer range and bandwidth
00199     char              chMaxAccRange_selected;
00200     char              chBW_selected;
00201     int               iCalib_CS;
00202 
00203     // internal Sub20 device data
00204     sub_handle        subhndl;                                               //handle for subdevice
00205     bool              bSubDeviceOpen;                   //initialization flag
00206     bool              bSubDeviceConfigured;     //verify if subdevice is configured
00207     std::string       strSerial;                                //Serial number of SUB20 device
00208 
00210     double            bma180data_to_double(char, char, bma180_cmd::eSensorType, int *,  double);
00211 
00213     unsigned short    bma180data_to_uint(char, char, bma180_cmd::eSensorType );
00214 
00216     bool              read_biassettings(sub_handle, int, unsigned short*, unsigned short*, unsigned short*);
00217 
00219     bool              set_biassettings(sub_handle, int, unsigned short, unsigned short, unsigned short, bool);
00220 
00222     bool              read_byte_eeprom_sub20(char, char*, unsigned short, sub_handle);
00223 
00225     bool              write_bit_eeprom_sub20(char, unsigned short, unsigned short, char, unsigned short, sub_handle);
00226 
00228     void              confsens_on_sub20(OneSub20Config*, char, char);
00229 
00231     void              set_calibstatus(bool bCalibrate);
00232 };
00233 
00234 #endif /* MULT_BMA180_H_ */
00235 


bma180
Author(s): Lukas Marti, Nikhil Deshpande, Philip Roan (Maintained by Philip Roan)
autogenerated on Mon Oct 6 2014 10:10:49