From 16595d2f3bfe8b02060efa9400086ced38b541e2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 20 Jun 2016 08:38:26 +1000 Subject: [PATCH] SITL: auto-set AHRS_EKF_TYPE to 10 for XPlane and FlightAxis --- libraries/SITL/SIM_FlightAxis.cpp | 2 ++ libraries/SITL/SIM_XPlane.cpp | 3 +++ 2 files changed, 5 insertions(+) diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index f69f24bfd6..54c12abdde 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -48,6 +48,8 @@ FlightAxis::FlightAxis(const char *home_str, const char *frame_str) : if (colon) { controller_ip = colon+1; } + // FlightAxis sensor data is not good enough for EKF. Use fake EKF by default + AP_Param::set_default_by_name("AHRS_EKF_TYPE", 10); } /* diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index c549b4818e..13c2b163de 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -44,6 +44,9 @@ XPlane::XPlane(const char *home_str, const char *frame_str) : socket_in.bind("0.0.0.0", bind_port); printf("Waiting for XPlane data on UDP port %u and sending to port %u\n", (unsigned)bind_port, (unsigned)xplane_port); + + // XPlane sensor data is not good enough for EKF. Use fake EKF by default + AP_Param::set_default_by_name("AHRS_EKF_TYPE", 10); } /*