mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: make sure AP_Vehicle::fast_loop() gets called
This commit is contained in:
parent
1358e39ffd
commit
3515dc9322
@ -266,6 +266,8 @@ void Copter::fast_loop()
|
|||||||
if (should_log(MASK_LOG_ANY)) {
|
if (should_log(MASK_LOG_ANY)) {
|
||||||
Log_Sensor_Health();
|
Log_Sensor_Health();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
AP_Vehicle::fast_loop();
|
||||||
}
|
}
|
||||||
|
|
||||||
// start takeoff to given altitude (for use by scripting)
|
// start takeoff to given altitude (for use by scripting)
|
||||||
|
Loading…
Reference in New Issue
Block a user