diff --git a/libraries/APM_BMP085/APM_BMP085.cpp b/libraries/APM_BMP085/APM_BMP085.cpp index 0e7000ad5a..d3c1872fec 100644 --- a/libraries/APM_BMP085/APM_BMP085.cpp +++ b/libraries/APM_BMP085/APM_BMP085.cpp @@ -52,14 +52,16 @@ APM_BMP085_Class::APM_BMP085_Class() } // Public Methods ////////////////////////////////////////////////////////////// -void APM_BMP085_Class::Init(void) +void APM_BMP085_Class::Init(int initialiseWireLib) { unsigned char tmp; byte buff[22]; int i=0; pinMode(BMP085_EOC,INPUT); // End Of Conversion (PC7) input - Wire.begin(); + + if( initialiseWireLib != 0 ) + Wire.begin(); oss = 3; // Over Sampling setting 3 = High resolution BMP085_State = 0; // Initial state @@ -244,7 +246,7 @@ APM_BMP085_HIL_Class::APM_BMP085_HIL_Class() } // Public Methods ////////////////////////////////////////////////////////////// -void APM_BMP085_HIL_Class::Init(void) +void APM_BMP085_HIL_Class::Init(int initialiseWireLib) { BMP085_State=1; } diff --git a/libraries/APM_BMP085/APM_BMP085.h b/libraries/APM_BMP085/APM_BMP085.h index b1d2093bb8..c874be3671 100644 --- a/libraries/APM_BMP085/APM_BMP085.h +++ b/libraries/APM_BMP085/APM_BMP085.h @@ -25,7 +25,7 @@ class APM_BMP085_Class //int32_t Press0; // Pressure at sea level APM_BMP085_Class(); // Constructor - void Init(); + void Init(int initialiseWireLib = 1); uint8_t Read(); }; @@ -41,7 +41,7 @@ class APM_BMP085_HIL_Class //int Altitude; uint8_t oss; APM_BMP085_HIL_Class(); // Constructor - void Init(); + void Init(int initialiseWireLib = 1); uint8_t Read(); void setHIL(float Temp, float Press); };