bmp085.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 
00051 #ifndef BMP085_H_
00052 #define BMP085_H_
00053 
00054 #include <cmath>
00055 #include <unistd.h> // for the sleep function
00056 
00057 #include <bosch_drivers_sensor_driver.hpp>
00058 #include <bosch_drivers_hardware_interface.hpp>
00059 
00060 #include "bmp085_parameters.hpp"
00061 
00062 using namespace bosch_drivers_common;
00063 
00073 class BMP085: public sensor_driver, public BMP085Parameters
00074 {
00075 public:
00076 
00083   static const uint8_t PRESSURE_OSRS_0 = 0x34; // 4.5 [ms]
00084   static const uint8_t PRESSURE_OSRS_1 = 0x74; // 7.5 [ms]
00085   static const uint8_t PRESSURE_OSRS_2 = 0xB4; // 13.5 [ms]
00086   static const uint8_t PRESSURE_OSRS_3 = 0xF4; // 25.5 [ms]
00087  
00088   static const uint8_t INPUT_REG_ADDRESS = 0xF4;
00089   
00090   // UT is the temperature data. To calculate it, 
00091   //   UT = MSB<<8 + LSB
00092   // UP is the pressure data.  To calculate it, 
00093   //   UP = (MSB<<16 + LSB<<8 +XLSB) >> (8 - oss)
00094   // where oss is the oversample setting (0,1,2, or 3). 
00095   static const uint8_t MEAS_OUTPUT_MSB  = 0xF6;
00096   static const uint8_t MEAS_OUTPUT_LSB  = 0xF7;
00097   static const uint8_t MEAS_OUTPUT_XLSB = 0xF8;
00098 
00099   enum sampling_mode
00100   {
00101     ULTRA_LOW_POWER       = 0,
00102     STANDARD              = 1,
00103     HIGH                  = 2,
00104     ULTRA_HIGH_RESOLUTION = 3
00105   };
00106 
00107   BMP085( bosch_hardware_interface* hw );
00108   ~BMP085(); 
00109 
00110   // inheritted from sensor_driver
00111   uint8_t getDeviceAddress(); // depends on protocol_.
00112   
00121   bool initialize();
00122  
00132   bool takeMeasurement();
00133   
00143   bool getPressureData( void );
00144   
00151   bool getTemperatureData( void );
00152   
00156   double getTemperature();
00157 
00161   double getPressure();
00162 
00171   double getAltitude( void );
00172  
00180   double calcAltitude( double input_pressure );
00181 
00188   void setPressureAtSeaLevel( double pressure );
00189 
00190 private:
00191   // BMP085 Register Addresses
00192   static const uint8_t DEVICE_ADDRESS = 0x77; // the address without the READ/WRITE bit.
00193  
00194   static const uint8_t ADDRESS_WRITE = 0xEE;
00195   static const uint8_t ADDRESS_READ  = 0xEF;
00196  
00197   static const uint8_t ADDRESS_AC1_MSB = 0xAA;
00198   static const uint8_t ADDRESS_AC1_LSB = 0xAB;
00199   static const uint8_t ADDRESS_AC2_MSB = 0xAC;
00200   static const uint8_t ADDRESS_AC2_LSB = 0xAD;
00201   static const uint8_t ADDRESS_AC3_MSB = 0xAE;
00202   static const uint8_t ADDRESS_AC3_LSB = 0xAF;
00203   static const uint8_t ADDRESS_AC4_MSB = 0xB0;
00204   static const uint8_t ADDRESS_AC4_LSB = 0xB1; 
00205   static const uint8_t ADDRESS_AC5_MSB = 0xB2;
00206   static const uint8_t ADDRESS_AC5_LSB = 0xB3;
00207   static const uint8_t ADDRESS_AC6_MSB = 0xB4;
00208   static const uint8_t ADDRESS_AC6_LSB = 0xB5;
00209   static const uint8_t ADDRESS_B1_MSB  = 0xB6;
00210   static const uint8_t ADDRESS_B1_LSB  = 0xB7;
00211   static const uint8_t ADDRESS_B2_MSB  = 0xB8;
00212   static const uint8_t ADDRESS_B2_LSB  = 0xB9;
00213   static const uint8_t ADDRESS_MB_MSB  = 0xBA;
00214   static const uint8_t ADDRESS_MB_LSB  = 0xBB;
00215   static const uint8_t ADDRESS_MC_MSB  = 0xBC;
00216   static const uint8_t ADDRESS_MC_LSB  = 0xBD;
00217   static const uint8_t ADDRESS_MD_MSB  = 0xBE;
00218   static const uint8_t ADDRESS_MF_LSB  = 0xBF;
00219  
00224   static const uint8_t ADDRESS_TEMP_REQUEST  = 0x2E;
00225 
00232   short oss; // oversample setting, which is essentially sampling_mode.
00233 
00245   short AC1, AC2, AC3;
00246   unsigned short AC4, AC5, AC6;
00247   short B1, B2;
00248   long B5; 
00249   short MB, MC, MD;
00250   long UT, UP;
00251   
00255   long T;
00256   
00260   long p; 
00261 
00266   double pressure_at_sea_level_;
00267 
00271   double altitude_;
00272 
00278   double temperature_; 
00279 
00285   double pressure_;
00286 
00287   bool writeToReg( uint8_t reg, uint8_t value );
00288 };
00289 
00290 #endif // BMP085_H_


bmp085_driver
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Sat Dec 28 2013 16:49:18