mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: auto-set AHRS_EKF_TYPE to 10 for XPlane and FlightAxis
This commit is contained in:
parent
6ecf0daa9f
commit
16595d2f3b
@ -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);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user