mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_IMU: added num_samples_available to allow main loop timing to be synced with arrival of new data from IMU.
This commit is contained in:
parent
3901387c8d
commit
38feee9c61
@ -257,3 +257,9 @@ float AP_IMU_INS::get_gyro_drift_rate(void)
|
||||
{
|
||||
return _ins->get_gyro_drift_rate();
|
||||
}
|
||||
|
||||
/// Get number of samples read from the sensors
|
||||
uint16_t AP_IMU_INS::num_samples_available(void)
|
||||
{
|
||||
return _ins->num_samples_available();
|
||||
}
|
||||
|
@ -55,6 +55,9 @@ public:
|
||||
virtual bool update(void);
|
||||
virtual bool new_data_available(void);
|
||||
|
||||
/// Get number of samples read from the sensors
|
||||
virtual uint16_t num_samples_available(void);
|
||||
|
||||
// for jason
|
||||
virtual float gx() {
|
||||
return _sensor_cal[0];
|
||||
@ -95,7 +98,6 @@ public:
|
||||
}
|
||||
virtual float get_gyro_drift_rate(void);
|
||||
|
||||
|
||||
private:
|
||||
AP_InertialSensor * _ins; ///< INS provides an axis and unit correct sensor source.
|
||||
|
||||
|
@ -41,6 +41,11 @@ bool IMU::new_data_available(void) {
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t IMU::num_samples_available(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
float IMU::gx(void) {
|
||||
return 0.0;
|
||||
}
|
||||
|
@ -62,9 +62,18 @@ public:
|
||||
///
|
||||
virtual bool update(void);
|
||||
|
||||
// true if new data is available from the sensors
|
||||
/// Check if new sensor data is available
|
||||
///
|
||||
/// @returns true if new data is available from the sensors
|
||||
///
|
||||
virtual bool new_data_available(void);
|
||||
|
||||
/// Get number of samples read from the sensors
|
||||
///
|
||||
/// @returns number of samples read from the sensors
|
||||
///
|
||||
virtual uint16_t num_samples_available(void);
|
||||
|
||||
/// Fetch the current gyro values
|
||||
///
|
||||
/// @returns vector of rotational rates in radians/sec
|
||||
|
Loading…
Reference in New Issue
Block a user