bma180.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 
00037 /*********************************************************************
00038  *
00039  * Disclaimer
00040  *
00041  * This source code is not officially released or supported by Bosch Sensortec.
00042  * Please contact the listed authors with bugs or other modifications.
00043  * If you would like the official Bosch Sensortec drivers, please contact:
00044  * contact@bosch-sensortec.com
00045  *
00046  *********************************************************************/
00047  
00048 //\Author Joshua Vasquez and  Philip Roan, Robert Bosch LLC
00049 
00050 #ifndef BMA180_H_
00051 #define BMA180_H_
00052 
00053 #include <cmath>  // for atan2
00054 #include <unistd.h> // for the sleep function
00055 
00056 #include <bosch_drivers_sensor_driver.hpp>
00057 #include <bosch_drivers_hardware_interface.hpp>
00058 
00059 #include "bma180_parameters.hpp"
00060 
00061 using namespace bosch_drivers_common;
00062 
00071 class BMA180: public sensor_driver, public BMA180Parameters
00072 {
00073 public:
00074   // Constructor
00075   BMA180( bosch_hardware_interface* hw ); 
00076   // Destructor
00077   ~BMA180();
00078     
00079   // Initialize the hardware interface so it can communicate with the bma180:
00080   bool initialize();
00081    
00082   // Measurement Methods
00083   bool takeMeasurement();
00084   bool getAccelData();
00085   double getAccelX();
00086   double getAccelY();
00087   double getAccelZ();
00088   double getStaticPitch(); // returns the pitch.  Measuring while moving is a bad idea, for now.
00089   double getStaticRoll();  
00090    
00091   double getTemperature();
00092   
00093   // Preferance Adjustments
00094   bool EnableWriting(); // must be called to perform any writes.
00095   bool Calibrate();  // a software routine for "re-zeroing the output."
00096   bool CoarseCalibrate();
00097   bool TwoStepCoarseCalibrate();
00098   bool FullCalibration();
00099   bool softReset();
00100   bool DisableI2C(); // to get bug-free SPI readings.
00101   bool changeAccelRange(); 
00102   bool changeBandwidth();
00103   //bool togglePreCalOffsets(bool choice);
00104   bool setEnOffsetBit( uint8_t bit );
00105   
00106   //returns the way the sensor identifies itself to the hardware interface.
00107   uint8_t getDeviceAddress(); 
00108 
00109   // Inheretted Methods: (from bma180_parameters)
00110   //bool setProtocol(interface_protocol protocol);
00111   //bool setFrequency(int frequency);
00112   //bool setPin( uint8_t pin);       
00113   //bool setSlaveAddressBit(bool choice); // choose between two device addresses. 
00114   //bool setByteOrder(uint8_t value);
00115   //bool setSpiMode(uint8_t mode);
00116   //bool setRange(accel_range new_range);
00117   //double        getSensitivity(); // returns sensitivity
00118   //interface_protocol  getProtocol();
00119   //int         getFrequency();
00120   //int*         getFlags();
00121   //int         getPin();  // SPI, GPIO only
00122   //uint8_t       getSlaveAddressBit();
00123 
00124   /* ----- MEMBERS ----- */
00125   double AccelX_;
00126   double AccelY_;
00127   double AccelZ_;
00128   double Temperature_;
00129   double StaticPitch_;
00130   double StaticRoll_;  
00131   
00132   double TempSlope_;
00133   
00134   
00135 protected:
00136   // BMA180 Register Definitions
00137 
00142   static const uint8_t SLAVE_ADDRESS0 = 0x40;
00143 
00148   static const uint8_t SLAVE_ADDRESS1 = 0x41; 
00149 
00150   // The Acceleration Data Registers
00151   static const uint8_t ADDRESS_ACCLXYZ     = 0x02;
00152   static const uint8_t ADDRESS_ACCLX_MSB   = 0x03;
00153   static const uint8_t ADDRESS_ACCLY_LSB   = 0x04;
00154   static const uint8_t ADDRESS_ACCLY_MSB   = 0x05;
00155   static const uint8_t ADDRESS_ACCLZ_LSB   = 0x06;
00156   static const uint8_t ADDRESS_ACCLZ_MSB   = 0x07;
00157   static const uint8_t ADDRESS_TEMPERATURE = 0x08;
00158 
00159   // Four registers for storing our own data
00160   static const uint8_t ADDRESS_EE_CD1 = 0x4C;
00161   static const uint8_t ADDRESS_EE_CD2 = 0x4D;
00162   static const uint8_t ADDRESS_CD1    = 0x2C;
00163   static const uint8_t ADDRESS_CD2    = 0x2D;
00164 
00165   static const uint8_t ADDRESS_VER         = 0x00;  
00166   static const uint8_t ADDRESS_STATUS_REG1 = 0x09;
00167   static const uint8_t ADDRESS_STATUS_REG2 = 0x0A;
00168   static const uint8_t ADDRESS_STATUS_REG3 = 0x0B;
00169   static const uint8_t ADDRESS_STATUS_REG4 = 0x0C;
00170   static const uint8_t ADDRESS_CTRLREG0    = 0x0D;
00171   static const uint8_t ADDRESS_CTRLREG1    = 0x0E;
00172   static const uint8_t ADDRESS_CTRLREG2    = 0x0F;
00173   static const uint8_t ADDRESS_CTRL_REG4   = 0x22;
00174 
00176   static const uint8_t ADDRESS_EE_OFFSET_Z    = 0x5A; 
00177   static const uint8_t ADDRESS_EE_OFFSET_Y    = 0x59;  
00178   static const uint8_t ADDRESS_EE_OFFSET_X    = 0x58;    
00179   static const uint8_t ADDRESS_EE_OFFSET_T    = 0x57;  
00180   static const uint8_t ADDRESS_EE_OFFSET_LSB2 = 0x56;  
00181   static const uint8_t ADDRESS_EE_OFFSET_LSB1 = 0x55;  
00182   static const uint8_t ADDRESS_EE_GAIN_Z      = 0x54;  
00183   static const uint8_t ADDRESS_EE_GAIN_Y      = 0x53;  
00184   static const uint8_t ADDRESS_EE_GAIN_X      = 0x52;  
00185   static const uint8_t ADDRESS_EE_GAIN_T      = 0x51;  
00186 
00188   static const uint8_t ADDRESS_OFFSET_Z    = 0x3A;
00189   static const uint8_t ADDRESS_OFFSET_Y    = 0x39;
00190   static const uint8_t ADDRESS_OFFSET_X    = 0x38;
00191   static const uint8_t ADDRESS_OFFSET_T    = 0x37;
00192   static const uint8_t ADDRESS_OFFSET_LSB2 = 0x36;
00193   static const uint8_t ADDRESS_OFFSET_LSB1 = 0x35;
00194   static const uint8_t ADDRESS_GAIN_Z      = 0x34;
00195   static const uint8_t ADDRESS_GAIN_Y      = 0x33;
00196   static const uint8_t ADDRESS_GAIN_X      = 0x32;
00197   static const uint8_t ADDRESS_GAIN_T      = 0x31;
00198 
00200   static const uint8_t ADDRESS_BW_TCS = 0x20;
00201 
00203   static const uint8_t ADDRESS_SOFTRESET = 0x10;
00204   static const uint8_t CMD_SOFTRESET     = 0xB6;
00205 
00207   static const uint8_t ADDRESS_HIGH_DUR = 0x27;
00208   static const uint8_t CMD_DISABLE_I2C  = 0x01;
00209 
00211 
00212   // BitFlags: CTRL_REG0
00213   // Enable Writing
00214   static const uint8_t ee_w = 4; // 1 bit of data < 3 > 
00215 
00216   // BitFlags: ADDRESS_OFFSET_LSB1
00217   // Changing range
00218   static const uint8_t range = 1; // 3 bits of data  < 3:1 >
00219 
00220   // BitFlags: ADDRESS_BW_TCS
00221   // Changing Bandwidth
00222   static const uint8_t bw = 4;
00223  
00224   // BitFlags: CTRL_REG1
00225   // Enable pre-calibrated offset flags: see Datasheet
00226   static const uint8_t en_offset_x = 7;
00227   static const uint8_t en_offset_y = 6;
00228   static const uint8_t en_offset_z = 5;
00229  
00230   // BitFlags: ADDRESS_STATUS_REG1
00231   // Check if calibration has been completed:
00232   static const uint8_t offset_st_s = 1;
00233  
00234   // BitFlags: ADDRESS_CTRL_REG4
00235   // Begin a calibration routine:
00236   static const uint8_t offset_finetuning = 0; // 2 bits of data: < 1:0 >
00237 
00238 
00239   bool readReg( uint8_t reg, uint8_t* value );             
00240   bool writeToReg( uint8_t reg, uint8_t value );
00241   bool writeToRegAndVerify( uint8_t reg, uint8_t value, uint8_t expected_value );
00242   bool readSensorData( uint8_t reg, uint8_t* value, uint8_t num_bytes );  
00243 };
00244 
00245 #endif // BMA180_H_


bma180_driver
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Mon Oct 6 2014 10:10:00