APM_Compass - 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@883 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
rmackay9@yahoo.com 2010-11-22 12:53:55 +00:00
parent e930dacb4d
commit 39b86313a2
2 changed files with 6 additions and 5 deletions

View File

@ -66,13 +66,14 @@ APM_Compass_Class::APM_Compass_Class() : orientation(0), declination(0.0)
}
// Public Methods //////////////////////////////////////////////////////////////
bool APM_Compass_Class::Init(void)
bool APM_Compass_Class::Init(int initialiseWireLib)
{
unsigned long currentTime = millis(); // record current time
int numAttempts = 0;
int success = 0;
Wire.begin();
if( initialiseWireLib != 0 )
Wire.begin();
delay(10);
@ -245,7 +246,7 @@ APM_Compass_HIL_Class::APM_Compass_HIL_Class() : orientation(0), declination(0.0
}
// Public Methods //////////////////////////////////////////////////////////////
bool APM_Compass_HIL_Class::Init(void)
bool APM_Compass_HIL_Class::Init(int initialiseWireLib)
{
unsigned long currentTime = millis(); // record current time
int numAttempts = 0;

View File

@ -75,7 +75,7 @@ class APM_Compass_Class
unsigned long lastUpdate;
APM_Compass_Class(); // Constructor
bool Init();
bool Init(int initialiseWireLib = 1);
void Read();
void Calculate(float roll, float pitch);
void SetOrientation(const Matrix3f &rotationMatrix);
@ -101,7 +101,7 @@ class APM_Compass_HIL_Class
unsigned long lastUpdate;
APM_Compass_HIL_Class(); // Constructor
bool Init();
bool Init(int initialiseWireLib = 1);
void Read();
void Calculate(float roll, float pitch);
void SetOrientation(const Matrix3f &rotationMatrix);