AP_Mission: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:12:21 +09:00 committed by Randy Mackay
parent 8257e6ab89
commit f20a4e413c
1 changed files with 3 additions and 3 deletions

View File

@ -43,10 +43,10 @@ void AP_Mission::init()
// prevent an easy programming error, this will be optimised out
if (sizeof(union Content) != 12) {
hal.scheduler->panic("AP_Mission Content must be 12 bytes");
AP_HAL::panic("AP_Mission Content must be 12 bytes");
}
_last_change_time_ms = hal.scheduler->millis();
_last_change_time_ms = AP_HAL::millis();
}
/// start - resets current commands to point to the beginning of the mission
@ -454,7 +454,7 @@ bool AP_Mission::write_cmd_to_storage(uint16_t index, Mission_Command& cmd)
_storage.write_block(pos_in_storage+3, cmd.content.bytes, 12);
// remember when the mission last changed
_last_change_time_ms = hal.scheduler->millis();
_last_change_time_ms = AP_HAL::millis();
// return success
return true;