SITL: auto-set AHRS_EKF_TYPE to 10 for XPlane and FlightAxis

This commit is contained in:
Andrew Tridgell 2016-06-20 08:38:26 +10:00
parent 6ecf0daa9f
commit 16595d2f3b
2 changed files with 5 additions and 0 deletions

View File

@ -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);
}
/*

View File

@ -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);
}
/*