Browse Source

AP_AHRS: remove check for AVR CPUs

Remove the checks for HAL_CPU_CLASS > HAL_CPU_CLASS_16 and
HAL_CPU_CLASS >= HAL_CPU_CLASS_75. Corresponding dead code will be
removed on separate commits.
mission-4.1.18
Lucas De Marchi 9 years ago committed by Andrew Tridgell
parent
commit
da86e29c27
  1. 4
      libraries/AP_AHRS/AP_AHRS_DCM.cpp
  2. 4
      libraries/AP_AHRS/AP_AHRS_DCM.h

4
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -597,7 +597,6 @@ AP_AHRS_DCM::drift_correction(float deltat)
} }
//update _accel_ef_blended //update _accel_ef_blended
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) { if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) {
float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f; float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f;
// slew _imu1_weight over one second // slew _imu1_weight over one second
@ -606,9 +605,6 @@ AP_AHRS_DCM::drift_correction(float deltat)
} else { } else {
_accel_ef_blended = _accel_ef[_ins.get_primary_accel()]; _accel_ef_blended = _accel_ef[_ins.get_primary_accel()];
} }
#else
_accel_ef_blended = _accel_ef[_ins.get_primary_accel()];
#endif // HAL_CPU_CLASS >= HAL_CPU_CLASS_75
// keep a sum of the deltat values, so we know how much time // keep a sum of the deltat values, so we know how much time
// we have integrated over // we have integrated over

4
libraries/AP_AHRS/AP_AHRS_DCM.h

@ -47,9 +47,7 @@ public:
_last_wind_time(0), _last_wind_time(0),
_last_airspeed(0.0f), _last_airspeed(0.0f),
_last_consistent_heading(0), _last_consistent_heading(0),
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
_imu1_weight(0.5f), _imu1_weight(0.5f),
#endif
_last_failure_ms(0), _last_failure_ms(0),
_last_startup_ms(0) _last_startup_ms(0)
{ {
@ -200,9 +198,7 @@ private:
// estimated wind in m/s // estimated wind in m/s
Vector3f _wind; Vector3f _wind;
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
float _imu1_weight; float _imu1_weight;
#endif
// last time AHRS failed in milliseconds // last time AHRS failed in milliseconds
uint32_t _last_failure_ms; uint32_t _last_failure_ms;

Loading…
Cancel
Save