mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
IMU: added get_gyro_drift_rate() interface
this just calls down to the InertialSensor layer
This commit is contained in:
parent
f46fba54dc
commit
f4b1dae7cf
@ -250,3 +250,10 @@ AP_IMU_INS::update(void)
|
||||
bool AP_IMU_INS::new_data_available(void) {
|
||||
return _ins->new_data_available();
|
||||
}
|
||||
|
||||
/// return the maximum gyro drift rate in radians/s/s. This
|
||||
/// depends on what gyro chips are being used
|
||||
float AP_IMU_INS::get_gyro_drift_rate(void)
|
||||
{
|
||||
return _ins->get_gyro_drift_rate();
|
||||
}
|
||||
|
@ -64,6 +64,7 @@ public:
|
||||
virtual void ax(const float v) { _sensor_cal[3] = v; }
|
||||
virtual void ay(const float v) { _sensor_cal[4] = v; }
|
||||
virtual void az(const float v) { _sensor_cal[5] = v; }
|
||||
virtual float get_gyro_drift_rate(void);
|
||||
|
||||
private:
|
||||
AP_InertialSensor *_ins; ///< INS provides an axis and unit correct sensor source.
|
||||
|
@ -67,6 +67,8 @@ public:
|
||||
// dummy save method
|
||||
void save(void) { }
|
||||
|
||||
float get_gyro_drift_rate(void) { return 0; }
|
||||
|
||||
private:
|
||||
/// set true when new data is delivered
|
||||
bool _updated;
|
||||
|
@ -41,3 +41,4 @@ float IMU::az(void) { return 0.0; }
|
||||
void IMU::ax(const float v) { }
|
||||
void IMU::ay(const float v) { }
|
||||
void IMU::az(const float v) { }
|
||||
float IMU::get_gyro_drift_rate(void) { return 0; }
|
||||
|
@ -84,6 +84,10 @@ public:
|
||||
///
|
||||
float get_delta_time(void) { return _sample_time * 1.0e-6; }
|
||||
|
||||
/// return the maximum gyro drift rate in radians/s/s. This
|
||||
/// depends on what gyro chips are being used
|
||||
virtual float get_gyro_drift_rate(void);
|
||||
|
||||
/// A count of bad sensor readings
|
||||
///
|
||||
/// @todo This should be renamed, as there's no guarantee that sensors
|
||||
|
Loading…
Reference in New Issue
Block a user