mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_EFI: poll MS at 10Hz not 5Hz
This commit is contained in:
parent
fb1b2e870e
commit
25ec1730b4
@ -47,7 +47,7 @@ void AP_EFI_Serial_MS::update()
|
|||||||
copy_to_frontend();
|
copy_to_frontend();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (now - last_response_ms > 200) {
|
if (now - last_response_ms > 100) {
|
||||||
port->discard_input();
|
port->discard_input();
|
||||||
// Request an update from the realtime table (7).
|
// Request an update from the realtime table (7).
|
||||||
// The data we need start at offset 6 and ends at 129
|
// The data we need start at offset 6 and ends at 129
|
||||||
|
Loading…
Reference in New Issue
Block a user