mirror of https://github.com/ArduPilot/ardupilot
Sub: Move from micros() to AP_HAL::micros()
AP_HAL::micros() is a more common style around the rest of the project Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
4de371743e
commit
3701fc0937
|
@ -677,10 +677,10 @@ void Sub::load_parameters(void)
|
|||
hal.console->println("done.");
|
||||
}
|
||||
|
||||
uint32_t before = micros();
|
||||
uint32_t before = AP_HAL::micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(AP_HAL::micros() - before));
|
||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||
|
||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB);
|
||||
|
|
|
@ -723,5 +723,3 @@ public:
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
extern Sub sub;
|
||||
|
||||
using AP_HAL::micros;
|
||||
|
|
|
@ -14,7 +14,7 @@ static bool in_failsafe;
|
|||
void Sub::mainloop_failsafe_enable()
|
||||
{
|
||||
failsafe_enabled = true;
|
||||
failsafe_last_timestamp = micros();
|
||||
failsafe_last_timestamp = AP_HAL::micros();
|
||||
}
|
||||
|
||||
// Disable mainloop lockup failsafe
|
||||
|
|
Loading…
Reference in New Issue