From 004a4425cd03138812ab75ef192250cdebdd0c6e Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Sun, 13 Nov 2011 13:45:23 +1100 Subject: [PATCH] barometer: add purple_hardware option to Init() this allows selection of right hardware at Init() time --- libraries/APM_BMP085/APM_BMP085.cpp | 28 +++++++++++++++---- libraries/APM_BMP085/APM_BMP085.h | 3 +- libraries/APM_BMP085/APM_BMP085_hil.cpp | 2 +- libraries/APM_BMP085/APM_BMP085_hil.h | 2 +- .../APM_BMP085_test/APM_BMP085_test.pde | 10 ++++++- 5 files changed, 35 insertions(+), 10 deletions(-) diff --git a/libraries/APM_BMP085/APM_BMP085.cpp b/libraries/APM_BMP085/APM_BMP085.cpp index 7e007ac130..81dcc09c3b 100644 --- a/libraries/APM_BMP085/APM_BMP085.cpp +++ b/libraries/APM_BMP085/APM_BMP085.cpp @@ -33,6 +33,7 @@ */ + extern "C" { // AVR LibC Includes #include @@ -51,12 +52,21 @@ extern "C" { //{ //} +// the purple hardware needs to check the state of the +// chip using a direct IO port +// On Purple prerelease hw, the data ready port is hooked up to PE7, which +// is not available to the arduino digitalRead function. +#define BMP_DATA_READY() (_purple_hardware?(PINE&0x80):digitalRead(BMP085_EOC)) + + // Public Methods ////////////////////////////////////////////////////////////// -void APM_BMP085_Class::Init(int initialiseWireLib) +bool APM_BMP085_Class::Init(int initialiseWireLib, bool purple_hardware) { byte buff[22]; int i = 0; + _purple_hardware = purple_hardware; + pinMode(BMP085_EOC, INPUT); // End Of Conversion (PC7) input if( initialiseWireLib != 0 ) @@ -68,7 +78,9 @@ void APM_BMP085_Class::Init(int initialiseWireLib) // We read the calibration data registers Wire.beginTransmission(BMP085_ADDRESS); Wire.send(0xAA); - Wire.endTransmission(); + if (Wire.endTransmission() != 0) { + return false; + } Wire.requestFrom(BMP085_ADDRESS, 22); @@ -77,6 +89,9 @@ void APM_BMP085_Class::Init(int initialiseWireLib) buff[i] = Wire.receive(); // receive one byte i++; } + if (i != 22) { + return false; + } ac1 = ((int)buff[0] << 8) | buff[1]; ac2 = ((int)buff[2] << 8) | buff[3]; @@ -93,6 +108,7 @@ void APM_BMP085_Class::Init(int initialiseWireLib) //Send a command to read Temp Command_ReadTemp(); BMP085_State = 1; + return true; } /* @@ -103,14 +119,14 @@ uint8_t APM_BMP085_Class::Read() uint8_t result = 0; if (BMP085_State == 1){ - if (digitalRead(BMP085_EOC)){ + if (BMP_DATA_READY()) { ReadTemp(); // On state 1 we read temp BMP085_State++; Command_ReadPress(); } }else{ if (BMP085_State == 5){ - if (digitalRead(BMP085_EOC)){ + if (BMP_DATA_READY()){ ReadPress(); Calculate(); @@ -119,7 +135,7 @@ uint8_t APM_BMP085_Class::Read() result = 1; // New pressure reading } }else{ - if (digitalRead(BMP085_EOC)){ + if (BMP_DATA_READY()){ ReadPress(); Calculate(); BMP085_State++; @@ -310,4 +326,4 @@ void APM_BMP085_Class::Calculate() x1 = (x1 * 3038) >> 16; x2 = (-7357 * p) >> 16; Press = p + ((x1 + x2 + 3791) >> 4); -} \ No newline at end of file +} diff --git a/libraries/APM_BMP085/APM_BMP085.h b/libraries/APM_BMP085/APM_BMP085.h index 1e0eabd7b5..e89a01535f 100644 --- a/libraries/APM_BMP085/APM_BMP085.h +++ b/libraries/APM_BMP085/APM_BMP085.h @@ -19,9 +19,10 @@ class APM_BMP085_Class int32_t Press; //int Altitude; uint8_t oss; + bool _purple_hardware; //int32_t Press0; // Pressure at sea level - void Init(int initialiseWireLib = 1); + bool Init(int initialiseWireLib = 1, bool purple_hardware=false); uint8_t Read(); private: diff --git a/libraries/APM_BMP085/APM_BMP085_hil.cpp b/libraries/APM_BMP085/APM_BMP085_hil.cpp index 21fc3dce5a..1bafada55b 100644 --- a/libraries/APM_BMP085/APM_BMP085_hil.cpp +++ b/libraries/APM_BMP085/APM_BMP085_hil.cpp @@ -15,7 +15,7 @@ APM_BMP085_HIL_Class::APM_BMP085_HIL_Class() } // Public Methods ////////////////////////////////////////////////////////////// -void APM_BMP085_HIL_Class::Init(int initialiseWireLib) +void APM_BMP085_HIL_Class::Init(int initialiseWireLib, bool purple_hardware) { BMP085_State=1; } diff --git a/libraries/APM_BMP085/APM_BMP085_hil.h b/libraries/APM_BMP085/APM_BMP085_hil.h index b873213d56..d880766a8b 100644 --- a/libraries/APM_BMP085/APM_BMP085_hil.h +++ b/libraries/APM_BMP085/APM_BMP085_hil.h @@ -13,7 +13,7 @@ class APM_BMP085_HIL_Class int32_t Press; //int Altitude; uint8_t oss; - void Init(int initialiseWireLib = 1); + void Init(int initialiseWireLib = 1, bool purple_hardware=false); uint8_t Read(); void setHIL(float Temp, float Press); }; diff --git a/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde b/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde index 4d2d23fd16..168aa6ae31 100644 --- a/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde +++ b/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde @@ -3,6 +3,7 @@ Code by Jordi MuĂ’oz and Jose Julio. DIYDrones.com */ +#include #include #include // ArduPilot Mega BMP085 Library @@ -10,12 +11,19 @@ APM_BMP085_Class APM_BMP085; unsigned long timer; +FastSerialPort0(Serial); + +// set this to true on purple +static bool purple_hardware = false; + void setup() { Serial.begin(115200); Serial.println("ArduPilot Mega BMP085 library test"); Serial.println("Initialising barometer..."); delay(100); - APM_BMP085.Init(); // APM ADC initialization + if (!APM_BMP085.Init(1, purple_hardware)) { + Serial.println("Barometer initialisation FAILED\n"); + } Serial.println("initialisation complete."); delay(100); delay(1000); timer = millis();