mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
AP_IMU: added new_data_available() interface
This commit is contained in:
parent
a052aa8435
commit
626f8598ed
@ -235,3 +235,7 @@ AP_IMU_INS::update(void)
|
|||||||
// always updated
|
// always updated
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_IMU_INS::new_data_available(void) {
|
||||||
|
return _ins->new_data_available();
|
||||||
|
}
|
||||||
|
@ -51,6 +51,7 @@ public:
|
|||||||
virtual void init_gyro(void (*delay_cb)(unsigned long t) = delay,
|
virtual void init_gyro(void (*delay_cb)(unsigned long t) = delay,
|
||||||
void (*flash_leds_cb)(bool on) = NULL);
|
void (*flash_leds_cb)(bool on) = NULL);
|
||||||
virtual bool update(void);
|
virtual bool update(void);
|
||||||
|
virtual bool new_data_available(void);
|
||||||
|
|
||||||
// for jason
|
// for jason
|
||||||
virtual float gx() { return _sensor_cal[0]; }
|
virtual float gx() { return _sensor_cal[0]; }
|
||||||
|
@ -37,6 +37,8 @@ public:
|
|||||||
}
|
}
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
|
virtual bool new_data_available(void) { return true; }
|
||||||
|
|
||||||
float gx() { return 0; }
|
float gx() { return 0; }
|
||||||
float gy() { return 0; }
|
float gy() { return 0; }
|
||||||
float gz() { return 0; }
|
float gz() { return 0; }
|
||||||
|
@ -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::update(void) { return false; }
|
||||||
|
bool IMU::new_data_available(void) { return true; }
|
||||||
|
|
||||||
float IMU::gx(void) { return 0.0; }
|
float IMU::gx(void) { return 0.0; }
|
||||||
float IMU::gy(void) { return 0.0; }
|
float IMU::gy(void) { return 0.0; }
|
||||||
|
@ -62,6 +62,9 @@ public:
|
|||||||
///
|
///
|
||||||
virtual bool update(void);
|
virtual bool update(void);
|
||||||
|
|
||||||
|
// true if new data is available from the sensors
|
||||||
|
virtual bool new_data_available(void);
|
||||||
|
|
||||||
/// Fetch the current gyro values
|
/// Fetch the current gyro values
|
||||||
///
|
///
|
||||||
/// @returns vector of rotational rates in radians/sec
|
/// @returns vector of rotational rates in radians/sec
|
||||||
|
Loading…
Reference in New Issue
Block a user