bma180s.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 {
00061   const char FLAG_R             = {0x80};
00062   //Define BMA180 commands
00063   const char    ADDRESS_ACCLXYZ        = {0x02};  //read accel data
00064   const char    ADDRESS_VER            = {0x00};  //read version data
00065   const char    ADDRESS_STATREG1       = {0x09};
00066   const char    ADDRESS_STATREG2       = {0x0A};
00067   const char    ADDRESS_STATREG3       = {0x0B};
00068   const char    ADDRESS_STATREG4       = {0x0C};
00069   const char    ADDRESS_CTRLREG0       = {0x0D};
00070   const char    ADDRESS_CTRLREG1       = {0x0E};
00071   const char    ADDRESS_CTRLREG2       = {0x0F};
00072   const char    ADDRESS_SOFTRESET      = {0x10};
00073   const char    ADDRESS_EE_OFFSET_Z    = {0x5A};  // |
00074   const char    ADDRESS_EE_OFFSET_Y    = {0x59};  // |
00075   const char    ADDRESS_EE_OFFSET_X    = {0x58};  // |-> THIS IS THE EEPROM
00076   const char    ADDRESS_EE_OFFSET_T    = {0x57};  // |
00077   const char    ADDRESS_EE_OFFSET_LSB2 = {0x56};  // |
00078   const char    ADDRESS_EE_OFFSET_LSB1 = {0x55};  // |
00079   const char    ADDRESS_OFFSET_Z       = {0x3A};
00080   const char    ADDRESS_OFFSET_Y       = {0x39};
00081   const char    ADDRESS_OFFSET_X       = {0x38};
00082   const char    ADDRESS_OFFSET_T       = {0x37};
00083   const char    ADDRESS_OFFSET_LSB2    = {0x36};
00084   const char    ADDRESS_OFFSET_LSB1    = {0x35};
00085   const char    ADDRESS_EE_GAIN_Z      = {0x54};
00086   //-----------------------------------
00087   const char    ADDRESS_BWTCS          = {0x20};
00088   const char    ADDRESS_RANGE          = {0x35};
00089   //-----------------------------------
00090   const double  dFULLRANGELOOKUP[] = {1.0, 1.5, 2.0, 3.0, 4.0, 8.0, 16.0};
00091   const char    COMMAND_FULLSCALE_G[] = {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06};
00092   //-----------------------------------
00093   const double  dBWLOOKUP[] = {10, 20, 40, 75, 150, 300, 600, 1200};
00094   const char    COMMAND_BANDWIDTH_HZ[] = {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07};
00095   //-----------------------------------
00096   const char    COMMAND_SOFTRESET = {0xB6};
00097   const char    COMMAND_SET_EEW   = {0x01};
00098   //-----------------------------------
00099   enum eSensorType {eACCEL, eTEMP, eBIAS_X, eBIAS_Y, eBIAS_Z};
00100   //-----------------------------------
00101   const unsigned short MAX_NUM_SENSORS = 5;          //Defined by the Xdimax Unit (which supports 5 sensors per box)
00102   //-----------------------------------
00103   const double  dDEFAULT_MAXACC_g     = 16.0;
00104   const std::string     sSUB20SERIAL("0651");
00105   const double  dDEFAULT_BANDWIDTH_Hz = 300;
00106   const double  dDEFAULT_RATE_Hz      = 500;
00107   const bool    bDEFAULT_CALIBRATE    = false;
00108   const double  dCALIB_ACCURACY       = 0.05;
00109   //-----------------------------------
00110   const unsigned short uSERIALNUMLENGTH = 20;
00111   //-----------------------------------
00112   const short   iDEFAULT_CALIBCHIPSELECT= 0;            //this is out of range and ensures that no calibration is executed in case of error
00113 }
00114 
00115 //Define measurement output
00116 struct OneBma180Meas
00117 {
00118   bool        bMeasAvailable; //indicates true if a valid measurement is available
00119   int         iNumAccels;
00120   double      dAccX[bma180_cmd::MAX_NUM_SENSORS];
00121   double      dAccY[bma180_cmd::MAX_NUM_SENSORS];
00122   double      dAccZ[bma180_cmd::MAX_NUM_SENSORS];
00123   double      dTemp;
00124   ros::Time   dtomeas; //time tag measurement immediately in case of other delays
00125   std::string serial_number;
00126   int         chip_select[bma180_cmd::MAX_NUM_SENSORS];
00127 };
00128 
00129 
00131 
00137 class Bma180
00138 {
00139 public:
00141 
00153   Bma180( double max_acceleration_g, double dBandwidth_Hz, bool bCalibrate, double dRate_Hz, std::string sSub20Serial );
00154   
00156 
00160   ~Bma180();
00161 
00163 
00173   void GetMeasurements( std::list<OneBma180Meas>& );
00174 
00175 private:
00176 
00177   // structure for one bma180 configuration
00178   struct OneBma180Config
00179   {
00180     double         dFullScaleRange;
00181     double         dSensorBandwidth;
00182     bool           bConfigured;
00183     unsigned short uiBiasImageX;
00184     unsigned short uiBiasImageY;
00185     unsigned short uiBiasImageZ;
00186     double         iNumOfCalibMeas;
00187   };
00188   
00189 // structure for one Sub20 device configuration
00190   struct OneSub20Config
00191   {
00192     std::string     strSub20Serial;
00193     sub_handle      handle_subdev;
00194     sub_device      subdev;
00195     bool            bSubSPIConfigured;
00196     OneBma180Config Bma180Cluster[bma180_cmd::MAX_NUM_SENSORS];
00197   };
00198   std::list<OneSub20Config>   Sub20Device_list;
00199 
00200   // internal calibration flags
00201   bool              bExecuteCalibration;
00202   bool              bCalibrationCompleted;
00203   bma180_calibrate  calib_bma180;
00204   
00205   // internal selected accelerometer range and bandwidth
00206   char              chMaxAccRange_selected;
00207   char              chBW_selected;
00208   int               iCalib_CS;
00209   
00210   // internal Sub20 device data
00211   sub_handle        subhndl;              //handle for Sub20 device
00212   bool              bSubDeviceOpen;       //initialization flag
00213   bool              bSubDeviceConfigured; //verify if subdevice is configured
00214   std::string       serial_number;        //Serial number of Sub20 device
00215   
00217   double bma180data_to_double( char, char, bma180_cmd::eSensorType, int *,  double );
00218   
00220   unsigned short bma180data_to_uint( char, char, bma180_cmd::eSensorType );
00221   
00223   bool read_biassettings( sub_handle, int, unsigned short*, unsigned short*, unsigned short* );
00224   
00226   bool set_biassettings( sub_handle, int, unsigned short, unsigned short, unsigned short, bool );
00227   
00229   bool read_byte_eeprom_sub20( char, char*, unsigned short, sub_handle );
00230   
00232   bool write_bit_eeprom_sub20( char, unsigned short, unsigned short, char, unsigned short, sub_handle );
00233   
00235   void confsens_on_sub20( OneSub20Config*, char, char );
00236   
00238   void set_calibstatus( bool bCalibrate );
00239 };
00240 
00241 #endif /* MULT_BMA180_H_ */
00242 


bma180
Author(s): Lukas Marti, Nikhil Deshpande, Philip Roan (Maintained by Philip Roan)
autogenerated on Sat Dec 28 2013 16:50:12