mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_AHRS: changed default GPS lag to 1 sample
this is based on detailed logs from a LEA-6H and NEO-7N
This commit is contained in:
parent
870ec8a9bb
commit
a96840e194
@ -111,7 +111,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
||||
// @Range: 0 5
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GPS_DELAY", 12, AP_AHRS, _gps_delay, 2),
|
||||
AP_GROUPINFO("GPS_DELAY", 12, AP_AHRS, _gps_delay, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user