mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 16:03:58 -04:00
AP_Mission: example uses millis/micros/panic functions
This commit is contained in:
parent
f20a4e413c
commit
01e4265ce1
@ -768,8 +768,8 @@ void MissionTest::run_resume_test()
|
|||||||
mission.stop();
|
mission.stop();
|
||||||
|
|
||||||
// update the mission for 5 seconds (nothing should happen)
|
// update the mission for 5 seconds (nothing should happen)
|
||||||
uint32_t start_time = hal.scheduler->millis();
|
uint32_t start_time = AP_HAL::millis();
|
||||||
while(hal.scheduler->millis() - start_time < 5000) {
|
while(AP_HAL::millis() - start_time < 5000) {
|
||||||
mission.update();
|
mission.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -991,8 +991,8 @@ void MissionTest::run_set_current_cmd_while_stopped_test()
|
|||||||
mission.set_current_cmd(2);
|
mission.set_current_cmd(2);
|
||||||
|
|
||||||
// update the mission for 2 seconds (nothing should happen)
|
// update the mission for 2 seconds (nothing should happen)
|
||||||
uint32_t start_time = hal.scheduler->millis();
|
uint32_t start_time = AP_HAL::millis();
|
||||||
while(hal.scheduler->millis() - start_time < 2000) {
|
while(AP_HAL::millis() - start_time < 2000) {
|
||||||
mission.update();
|
mission.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1006,8 +1006,8 @@ void MissionTest::run_set_current_cmd_while_stopped_test()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// pause for two seconds
|
// pause for two seconds
|
||||||
start_time = hal.scheduler->millis();
|
start_time = AP_HAL::millis();
|
||||||
while(hal.scheduler->millis() - start_time < 2000) {
|
while(AP_HAL::millis() - start_time < 2000) {
|
||||||
mission.update();
|
mission.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user