AP_IMU: added new_data_available() interface

This commit is contained in:
Andrew Tridgell 2012-03-03 18:31:55 +11:00
parent a052aa8435
commit 626f8598ed
5 changed files with 11 additions and 0 deletions

View File

@ -235,3 +235,7 @@ AP_IMU_INS::update(void)
// always updated
return true;
}
bool AP_IMU_INS::new_data_available(void) {
return _ins->new_data_available();
}

View File

@ -51,6 +51,7 @@ public:
virtual void init_gyro(void (*delay_cb)(unsigned long t) = delay,
void (*flash_leds_cb)(bool on) = NULL);
virtual bool update(void);
virtual bool new_data_available(void);
// for jason
virtual float gx() { return _sensor_cal[0]; }

View File

@ -37,6 +37,8 @@ public:
}
//@}
virtual bool new_data_available(void) { return true; }
float gx() { return 0; }
float gy() { return 0; }
float gz() { return 0; }

View File

@ -30,6 +30,7 @@ void IMU::init_gyro(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(boo
{ }
bool IMU::update(void) { return false; }
bool IMU::new_data_available(void) { return true; }
float IMU::gx(void) { return 0.0; }
float IMU::gy(void) { return 0.0; }

View File

@ -62,6 +62,9 @@ public:
///
virtual bool update(void);
// true if new data is available from the sensors
virtual bool new_data_available(void);
/// Fetch the current gyro values
///
/// @returns vector of rotational rates in radians/sec