From a9dea35310bffea4d02f9b961eeaa5a9cdff7e09 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 3 Mar 2012 18:31:31 +1100 Subject: [PATCH] AP_InertialSensor: added new_data_available() interface --- libraries/AP_InertialSensor/AP_InertialSensor.h | 3 +++ libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 5 +++++ libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h | 1 + libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp | 5 +++++ libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h | 1 + libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp | 1 + libraries/AP_InertialSensor/AP_InertialSensor_Stub.h | 1 + 7 files changed, 17 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 1227122280..08067b8e1d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -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). */ diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 3cfd3aefeb..500bfe464d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -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; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index b6044c36d5..fe48070ca8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -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(); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp index 3f5e45fd0a..cbdf80fb30 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp @@ -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; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h index 5995dcfde5..48f43b1694 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h @@ -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(); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp index 4c917ae3b0..e88785e1c6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.cpp @@ -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; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.h b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.h index a78b995d16..aae2bd1393 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Stub.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Stub.h @@ -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();