Browse Source

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

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
16595d2f3b
  1. 2
      libraries/SITL/SIM_FlightAxis.cpp
  2. 3
      libraries/SITL/SIM_XPlane.cpp

2
libraries/SITL/SIM_FlightAxis.cpp

@ -48,6 +48,8 @@ FlightAxis::FlightAxis(const char *home_str, const char *frame_str) :
if (colon) { if (colon) {
controller_ip = colon+1; 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);
} }
/* /*

3
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); socket_in.bind("0.0.0.0", bind_port);
printf("Waiting for XPlane data on UDP port %u and sending to port %u\n", printf("Waiting for XPlane data on UDP port %u and sending to port %u\n",
(unsigned)bind_port, (unsigned)xplane_port); (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);
} }
/* /*

Loading…
Cancel
Save