From 01e4265ce1ac9176d2951be4b3985072ce36f4af Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Fri, 20 Nov 2015 12:12:32 +0900 Subject: [PATCH] AP_Mission: example uses millis/micros/panic functions --- .../examples/AP_Mission_test/AP_Mission_test.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp index a2ce511983..bed52a94f0 100644 --- a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp +++ b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp @@ -768,8 +768,8 @@ void MissionTest::run_resume_test() mission.stop(); // update the mission for 5 seconds (nothing should happen) - uint32_t start_time = hal.scheduler->millis(); - while(hal.scheduler->millis() - start_time < 5000) { + uint32_t start_time = AP_HAL::millis(); + while(AP_HAL::millis() - start_time < 5000) { mission.update(); } @@ -991,8 +991,8 @@ void MissionTest::run_set_current_cmd_while_stopped_test() mission.set_current_cmd(2); // update the mission for 2 seconds (nothing should happen) - uint32_t start_time = hal.scheduler->millis(); - while(hal.scheduler->millis() - start_time < 2000) { + uint32_t start_time = AP_HAL::millis(); + while(AP_HAL::millis() - start_time < 2000) { mission.update(); } @@ -1006,8 +1006,8 @@ void MissionTest::run_set_current_cmd_while_stopped_test() } // pause for two seconds - start_time = hal.scheduler->millis(); - while(hal.scheduler->millis() - start_time < 2000) { + start_time = AP_HAL::millis(); + while(AP_HAL::millis() - start_time < 2000) { mission.update(); }