AP_InertialSensor: added new_data_available() interface

This commit is contained in:
Andrew Tridgell 2012-03-03 18:31:31 +11:00
parent c80ec9a55c
commit a9dea35310
7 changed files with 17 additions and 0 deletions

View File

@ -20,6 +20,9 @@ class AP_InertialSensor
*/
virtual bool update() = 0;
// check if the sensors have new data
virtual bool new_data_available(void) = 0;
/* Getters for individual gyro axes.
* Gyros have correct coordinate frame and units (degrees per second).
*/

View File

@ -159,6 +159,11 @@ bool AP_InertialSensor_MPU6000::update( void )
return true;
}
bool AP_InertialSensor_MPU6000::new_data_available( void )
{
return _count != 0;
}
float AP_InertialSensor_MPU6000::gx() { return _gyro.x; }
float AP_InertialSensor_MPU6000::gy() { return _gyro.y; }
float AP_InertialSensor_MPU6000::gz() { return _gyro.z; }

View File

@ -20,6 +20,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor
/* Concrete implementation of AP_InertialSensor functions: */
bool update();
bool new_data_available();
float gx();
float gy();
float gz();

View File

@ -71,6 +71,11 @@ bool AP_InertialSensor_Oilpan::update()
return true;
}
bool AP_InertialSensor_Oilpan::new_data_available( void )
{
return _adc->new_data_available(_sensors);
}
float AP_InertialSensor_Oilpan::gx() { return _gyro.x; }
float AP_InertialSensor_Oilpan::gy() { return _gyro.y; }
float AP_InertialSensor_Oilpan::gz() { return _gyro.z; }

View File

@ -19,6 +19,7 @@ class AP_InertialSensor_Oilpan : public AP_InertialSensor
/* Concrete implementation of AP_InertialSensor functions: */
void init(AP_PeriodicProcess * scheduler);
bool update();
bool new_data_available();
float gx();
float gy();
float gz();

View File

@ -7,6 +7,7 @@ void AP_InertialSensor_Stub::init( AP_PeriodicProcess * scheduler ) {}
/*================ AP_INERTIALSENSOR PUBLIC INTERFACE ==================== */
bool AP_InertialSensor_Stub::update( void ) { return true; }
bool AP_InertialSensor_Stub::new_data_available( void ) { return true; }
float AP_InertialSensor_Stub::gx() { return 0.0f; }

View File

@ -19,6 +19,7 @@ class AP_InertialSensor_Stub : public AP_InertialSensor
/* Concrete implementation of AP_InertialSensor functions: */
bool update();
bool new_data_available();
float gx();
float gy();
float gz();