APM_BMP085 - added InitialiseWireLib parameter to Init function. This allows us to skip the Wire.begin which should only be called once.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@884 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
rmackay9@yahoo.com 2010-11-22 12:55:34 +00:00
parent 39b86313a2
commit 3d80d7e580
2 changed files with 7 additions and 5 deletions

View File

@ -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;
}

View File

@ -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);
};