Browse Source

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>
mission-4.1.18
Patrick José Pereira 7 years ago committed by Jacob Walser
parent
commit
3701fc0937
  1. 4
      ArduSub/Parameters.cpp
  2. 2
      ArduSub/Sub.h
  3. 2
      ArduSub/failsafe.cpp

4
ArduSub/Parameters.cpp

@ -677,10 +677,10 @@ void Sub::load_parameters(void) @@ -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);

2
ArduSub/Sub.h

@ -723,5 +723,3 @@ public: @@ -723,5 +723,3 @@ public:
extern const AP_HAL::HAL& hal;
extern Sub sub;
using AP_HAL::micros;

2
ArduSub/failsafe.cpp

@ -14,7 +14,7 @@ static bool in_failsafe; @@ -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…
Cancel
Save