bmp085.cpp
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 // ROS header for debugging output
00051 #include <ros/console.h>
00052 
00053 #include "bmp085_driver/bmp085.hpp"
00054 #include "bmp085_driver/bmp085_parameters.hpp"
00055 
00056 
00057 /**********************************************************************/
00058 // Constructor
00059 /**********************************************************************/
00060 BMP085::BMP085( bosch_hardware_interface* hw ) :
00061   sensor_driver( hw ),
00062   BMP085Parameters()
00063 {
00064   // set default pressure at sea level:
00065   pressure_at_sea_level_ = 101.325; // in [kPa]
00066 }
00067 
00068 
00069 /**********************************************************************/
00070 // Destructor
00071 /**********************************************************************/
00072 BMP085::~BMP085() 
00073 {
00074 }
00075 
00076 
00077 /**********************************************************************/
00078 // Initialization
00079 /**********************************************************************/
00080 bool BMP085::initialize()
00081 {  
00082   // Only I2C is supported for BMP085.  
00083   if( this->getProtocol() != I2C )
00084   {
00085     ROS_ERROR("BMP085::initialize(): You cannot read the BMP085 with this protocol");
00086     return false;
00087   }
00088 
00089   // Initialize the hardware interface with the selected parameters.
00090   if( hardware_->initialize() == false )
00091   {
00092     ROS_ERROR("BMP085::initialize(): Could not initialize a hardware interface!");
00093     return false;
00094   }
00095   
00096   // set oversampling setting:
00097   oss = this->getSamplingMode(); 
00098   ROS_INFO("Pressure Sensor Sampling Mode (oss): %d", oss);
00099 
00100   // Get all Calibration Constants.  
00101   // Luckily, they're all consecutively stored in memory, so we can just
00102   // read them all at once into one array using a multi-byte read.   
00103   uint8_t FullCalData[22];
00104    
00105   // Read 22 bytes of Calibration-constant data
00106  
00107   if( hardware_->read( this->getDeviceAddress(), this->getProtocol(), this->getFrequency(), this->getFlags(), (uint8_t)ADDRESS_AC1_MSB, FullCalData, 22 ) < 0 )
00108   {
00109     ROS_ERROR("BMP085::initialize(): Invalid Calibration data");
00110     return false;
00111   }
00112  
00113   // Compute calibration constants:
00114   AC1 = ((uint16_t)FullCalData[0]  <<8) | (uint16_t)FullCalData[1];
00115   AC2 = ((uint16_t)FullCalData[2]  <<8) | (uint16_t)FullCalData[3];
00116   AC3 = ((uint16_t)FullCalData[4]  <<8) | (uint16_t)FullCalData[5];
00117   AC4 = ((uint16_t)FullCalData[6]  <<8) | (uint16_t)FullCalData[7];
00118   AC5 = ((uint16_t)FullCalData[8]  <<8) | (uint16_t)FullCalData[9];
00119   AC6 = ((uint16_t)FullCalData[10] <<8) | (uint16_t)FullCalData[11];
00120  
00121   B1 =  ((uint16_t)FullCalData[12] <<8) | (uint16_t)FullCalData[13];
00122   B2 =  ((uint16_t)FullCalData[14] <<8) | (uint16_t)FullCalData[15];
00123 
00124   MB =  ((uint16_t)FullCalData[16] <<8) | (uint16_t)FullCalData[17];
00125   MC =  ((uint16_t)FullCalData[18] <<8) | (uint16_t)FullCalData[19];
00126   MD =  ((uint16_t)FullCalData[20] <<8) | (uint16_t)FullCalData[21];
00127 
00128   //ROS_INFO("%d",AC1); // for debugging
00129   return true;
00130 }
00131 
00132 
00133 /**********************************************************************/
00134 // measure both Temperature and Pressure
00135 /**********************************************************************/
00136 bool BMP085::takeMeasurement()
00137 {
00138   // pressure measurement depends on temperature, so get temperature first!
00139   //   Specifically, the B5 constant in the pressure calculation comes
00140   // from the temp calculation.
00141   if( this->getTemperatureData() == false )
00142     return false;
00143   if( this->getPressureData() == false )
00144     return false;
00145 
00146   return true;
00147 }
00148 
00149 
00150 /**********************************************************************/
00151 /**********************************************************************/
00152 uint8_t BMP085::getDeviceAddress()
00153 {
00154   // I2C is the only way the sensor can be read.  
00155   // Ensure I2C has been set:
00156   switch( this->getProtocol() )
00157   {
00158   case I2C:
00159     return DEVICE_ADDRESS;
00160     break;
00161   default:
00162     ROS_ERROR("BMP085::getDeviceAddress(): Protocol not set in parameters. Please set a protocol, and recompile.");
00163     return DEVICE_ADDRESS;
00164   } 
00165 }
00166 
00167 
00168 /**********************************************************************/
00169 /**********************************************************************/
00170 bool BMP085::getTemperatureData( void )  
00171 {
00172   /* Note: lots of casting! The Temperature is a uint16_t. 
00173    *   However, we need to access it's 8-bit MSB chunk 
00174    *   and 8-bit LSB chunk separately.  
00175    *   Then, we combine them into a uint16_t.
00176    */
00177   uint8_t MSB, LSB;
00178   
00179   if( writeToReg( INPUT_REG_ADDRESS, ADDRESS_TEMP_REQUEST ) == false )
00180   {
00181     ROS_ERROR("BMP085::getTemperatureData(): INVALID DATA");
00182     return false;
00183   }
00184  
00185   usleep( 4500 ); // sleep for 4.5 [ms] while BMP085 processes temperature.
00186   
00187   if( hardware_->read( this->getDeviceAddress(), this->getProtocol(), this->getFrequency(), this->getFlags(), MEAS_OUTPUT_MSB, &MSB, 1 ) < 0 )
00188   {
00189     ROS_ERROR("BMP085::getTemperatureData(): Invalid data"); 
00190     return false;
00191   }
00192   if( hardware_->read( this->getDeviceAddress(), this->getProtocol(), this->getFrequency(), this->getFlags(), MEAS_OUTPUT_LSB, &LSB, 1 ) < 0 )
00193   {
00194     ROS_ERROR("BMP085::getTemperatureData(): Invalid data"); 
00195     return false;
00196   }
00197  
00198   UT = ( (uint16_t)MSB << 8 ) + LSB;
00199 
00200   long X1, X2; 
00201   X1 = ( (UT - AC6) * AC5) >> 15; // Note: X>>15 == X/(pow(2,15))
00202   X2 = (MC << 11) / (X1 + MD); // Note: X<<11 == X<<(pow(2,11))
00203   // B5 is part of the class.
00204   B5 = X1 + X2;
00205   T = (B5 + 8) >> 4;
00206 
00207   temperature_ = (double)T * 0.1; 
00208  
00209   return true;
00210 }
00211 
00212 
00213 /**********************************************************************/
00214 /**********************************************************************/
00215 bool BMP085::getPressureData()
00216 {
00217   /* Note: The Pressure has up to 19 bits of data.
00218    * We need to combine three 8-bit numbers and shift them accordingly.
00219    */  
00220 
00221   uint8_t PressureRequest = PRESSURE_OSRS_0 + (oss<<6);
00222   
00223   if( writeToReg( INPUT_REG_ADDRESS, PressureRequest ) == false )
00224   {
00225     ROS_ERROR("BMP085::getPressureData():INVALID DATA");
00226     return false;
00227   }
00228  
00229   // Wait for the chip's pressure measurement to finish processing 
00230   // before accessing the data.  Wait time depends on the sampling mode.
00231   switch( oss )
00232   {
00233   case 0:
00234     usleep( 4500 ); 
00235     break;
00236   case 1:
00237     usleep( 7500 );
00238     break;
00239   case 2:
00240     usleep( 13500 );
00241     break;
00242   case 3:
00243     usleep( 25500 );
00244     break;
00245   default:
00246     usleep( 25500 );
00247     break;
00248   }
00249 
00250   unsigned char data[3]; 
00251   
00252   if( hardware_->read( this->getDeviceAddress(), this->getProtocol(), this->getFrequency(), this->getFlags(), MEAS_OUTPUT_MSB, data, 3 ) < 0 )
00253   {
00254     ROS_ERROR("BMP085::getPressureData():Invalid data");
00255     return false;
00256   }
00257 
00258   UP = (long)( ( ( (ulong)data[0]<<16) | ((ulong)data[1]<<8) | (ulong)data[2] ) >> (8-oss));
00259   // ROS_INFO("UP: %dl",UP);  // sanity check.
00260   long B3, B6, X1, X2, X3;  // coefficients derived from existing coefficients. 
00261   // Note: we calculated B5 from the temperature!
00262   ulong B4, B7;
00263   
00264   B6 = B5 - 4000;
00265   X1 = ( (B2 * ((B6 * B6)>>12)) >> 11 );
00266   X2 = ( ((long)AC2* B6) >> 11);
00267   X3 = X1 + X2;
00268   B3 = ( ( ( ((long)AC1*4) + X3)<< oss) + 2) >> 2;
00269   
00270   X1 = (((long)AC3*B6) >> 13);
00271   X2 = ( B1*((B6*B6) >> 12) ) >> 16;
00272   X3 = ( (X1 + X2) + 2 ) >> 2;
00273   B4 = ((long)AC4* (ulong)(X3 + 32768)) >> 15;
00274   
00275   B7 =  (ulong)(UP - B3)*(50000>>oss);
00276   if( B7 < 0x80000000 )
00277   {
00278     p = (B7 << 1)/B4;
00279   }
00280   else
00281   {
00282     p = (B7/B4) << 1;
00283   }
00284   X1 = (p >> 8)*(p >> 8);
00285   X1 = (X1*3038) >> 16;
00286   X2 = ((-7357)*p)>>16;
00287   p = p + ( ( X1 + X2 + 3791 ) >> 4);
00288 
00289   pressure_ = p / 1000.0; // in [kPa]
00290   //ROS_INFO("pressure: %f",pressure_);
00291   return true;
00292 }
00293 
00294 /**********************************************************************/
00295 /**********************************************************************/
00296 double BMP085::calcAltitude( double static_pressure )
00297 {
00298   // fancy math: barometric equation
00299   altitude_ = 44330 * (1 - pow( (static_pressure / pressure_at_sea_level_), (1/5.255) ));
00300   return altitude_;
00301 }
00302 
00303 
00304 /**********************************************************************/
00305 // returns the altitude based on the most recent pressure measurement
00306 /**********************************************************************/
00307 double BMP085::getAltitude()
00308 {
00309   return calcAltitude( pressure_ );
00310 }
00311 
00312 
00313 /**********************************************************************/
00314 /**********************************************************************/
00315 double BMP085::getTemperature()
00316 {
00317   return temperature_;
00318 }
00319 
00320 
00321 /**********************************************************************/
00322 /**********************************************************************/
00323 double BMP085::getPressure()
00324 {
00325   return pressure_;
00326 }
00327 
00328 
00329 /**********************************************************************/
00330 /**********************************************************************/
00331 void BMP085::setPressureAtSeaLevel( double pressure )
00332 {
00333   pressure_at_sea_level_ = pressure;
00334 }
00335 
00336 
00337 /**********************************************************************/
00338 // write a byte to a register
00339 /**********************************************************************/
00340 bool BMP085::writeToReg( uint8_t reg, uint8_t value )
00341 {
00342   if( hardware_->write( this->getDeviceAddress(), this->getProtocol(), this->getFrequency(), this->getFlags(), (uint8_t)reg, &value, 1 ) < 0 )
00343   {
00344     ROS_ERROR("could not write value to register."); 
00345     return false;
00346   }
00347   return true;
00348 }


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