Browse Source

AP_AHRS: remove AHRS_EKF_USE_ALWAYS define

This option now is passed when instantiating the code in ArduCopter, so
selecting the default value at compile time is not necessary anymore.

The motivation is to move vehicle specifc code out of the general
libraries. This patch shouldn't change behavior.
mission-4.1.18
Caio Marcelo de Oliveira Filho 9 years ago committed by Andrew Tridgell
parent
commit
f7c73fbb13
  1. 7
      libraries/AP_AHRS/AP_AHRS.h
  2. 7
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

7
libraries/AP_AHRS/AP_AHRS.h

@ -33,13 +33,6 @@ @@ -33,13 +33,6 @@
#include <AP_OpticalFlow/AP_OpticalFlow.h>
// Copter defaults to EKF on by default, all others off
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
# define AHRS_EKF_USE_ALWAYS 1
#else
# define AHRS_EKF_USE_ALWAYS 0
#endif
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter

7
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -43,12 +43,7 @@ public: @@ -43,12 +43,7 @@ public:
// Constructor
AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng,
NavEKF &_EKF1, NavEKF2 &_EKF2,
#if AHRS_EKF_USE_ALWAYS
Flags flags = FLAG_ALWAYS_USE_EKF
#else
Flags flags = FLAG_NONE
#endif
NavEKF &_EKF1, NavEKF2 &_EKF2, Flags flags = FLAG_NONE
) :
AP_AHRS_DCM(ins, baro, gps),
EKF1(_EKF1),

Loading…
Cancel
Save