mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: use scheduler.get_last_loop_time_s()
This commit is contained in:
parent
59868f425e
commit
f190ca0867
@ -124,7 +124,7 @@ void Rover::setup()
|
||||
void Rover::loop()
|
||||
{
|
||||
scheduler.loop();
|
||||
G_Dt = scheduler.get_filtered_loop_time();
|
||||
G_Dt = scheduler.get_last_loop_time_s();
|
||||
}
|
||||
|
||||
void Rover::update_soft_armed()
|
||||
|
Loading…
Reference in New Issue
Block a user