mirror of https://github.com/ArduPilot/ardupilot
AHRS: default EKF on for copter
This commit is contained in:
parent
053c5054f3
commit
9e731550fd
|
@ -117,7 +117,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
||||||
// @Description: This controls whether the NavEKF Kalman filter is used for attitude and position estimation
|
// @Description: This controls whether the NavEKF Kalman filter is used for attitude and position estimation
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EKF_USE", 13, AP_AHRS, _ekf_use, 0),
|
AP_GROUPINFO("EKF_USE", 13, AP_AHRS, _ekf_use, AHRS_EKF_USE_DEFAULT),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
|
@ -31,6 +31,13 @@
|
||||||
#include <AP_Baro.h>
|
#include <AP_Baro.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
|
|
||||||
|
// Copter defaults to EKF on by default, all others off
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||||
|
#define AHRS_EKF_USE_DEFAULT 1
|
||||||
|
#else
|
||||||
|
#define AHRS_EKF_USE_DEFAULT 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
#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_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
|
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
|
||||||
|
|
Loading…
Reference in New Issue