Tools: removed native_millis/micros

This commit is contained in:
Andrew Tridgell 2023-08-22 11:41:18 +10:00 committed by Peter Barker
parent 3752750f0a
commit c151d9bc3d
3 changed files with 25 additions and 25 deletions

View File

@ -284,7 +284,7 @@ void AP_Periph_FW::init()
#if AP_SCRIPTING_ENABLED #if AP_SCRIPTING_ENABLED
scripting.init(); scripting.init();
#endif #endif
start_ms = AP_HAL::native_millis(); start_ms = AP_HAL::millis();
} }
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY) #if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
@ -302,7 +302,7 @@ void AP_Periph_FW::update_rainbow()
if (rainbow_done) { if (rainbow_done) {
return; return;
} }
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
if (now - start_ms > 1500) { if (now - start_ms > 1500) {
rainbow_done = true; rainbow_done = true;
#if defined (HAL_PERIPH_ENABLE_NOTIFY) #if defined (HAL_PERIPH_ENABLE_NOTIFY)
@ -386,7 +386,7 @@ void AP_Periph_FW::update()
#endif #endif
static uint32_t last_led_ms; static uint32_t last_led_ms;
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
if (now - last_led_ms > 1000) { if (now - last_led_ms > 1000) {
last_led_ms = now; last_led_ms = now;
#ifdef HAL_GPIO_PIN_LED #ifdef HAL_GPIO_PIN_LED

View File

@ -214,7 +214,7 @@ static void handle_get_node_info(CanardInstance* canard_instance,
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {}; uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {};
uavcan_protocol_GetNodeInfoResponse pkt {}; uavcan_protocol_GetNodeInfoResponse pkt {};
node_status.uptime_sec = AP_HAL::native_millis() / 1000U; node_status.uptime_sec = AP_HAL::millis() / 1000U;
pkt.status = node_status; pkt.status = node_status;
pkt.software_version.major = AP::fwversion().major; pkt.software_version.major = AP::fwversion().major;
@ -492,7 +492,7 @@ static void handle_allocation_response(CanardInstance* canard_instance, CanardRx
{ {
// Rule C - updating the randomized time interval // Rule C - updating the randomized time interval
dronecan.send_next_node_id_allocation_request_at_ms = dronecan.send_next_node_id_allocation_request_at_ms =
AP_HAL::native_millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID)
@ -564,7 +564,7 @@ static void handle_beep_command(CanardInstance* canard_instance, CanardRxTransfe
hal.rcout->init(); hal.rcout->init();
hal.util->toneAlarm_init(AP_Notify::Notify_Buzz_Builtin); hal.util->toneAlarm_init(AP_Notify::Notify_Buzz_Builtin);
} }
buzzer_start_ms = AP_HAL::native_millis(); buzzer_start_ms = AP_HAL::millis();
buzzer_len_ms = req.duration*1000; buzzer_len_ms = req.duration*1000;
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY #ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
float volume = constrain_float(periph.g.buzz_volume/100.0f, 0, 1); float volume = constrain_float(periph.g.buzz_volume/100.0f, 0, 1);
@ -580,7 +580,7 @@ static void handle_beep_command(CanardInstance* canard_instance, CanardRxTransfe
static void can_buzzer_update(void) static void can_buzzer_update(void)
{ {
if (buzzer_start_ms != 0) { if (buzzer_start_ms != 0) {
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
if (now - buzzer_start_ms > buzzer_len_ms) { if (now - buzzer_start_ms > buzzer_len_ms) {
hal.util->toneAlarm_set_buzzer_tone(0, 0, 0); hal.util->toneAlarm_set_buzzer_tone(0, 0, 0);
buzzer_start_ms = 0; buzzer_start_ms = 0;
@ -829,7 +829,7 @@ static void can_safety_LED_update(void)
palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON); palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON);
break; break;
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: { case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: {
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
if (now - last_update_ms > 100) { if (now - last_update_ms > 100) {
last_update_ms = now; last_update_ms = now;
static uint8_t led_counter; static uint8_t led_counter;
@ -858,7 +858,7 @@ static void can_safety_button_update(void)
{ {
static uint32_t last_update_ms; static uint32_t last_update_ms;
static uint8_t counter; static uint8_t counter;
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
// send at 10Hz when pressed // send at 10Hz when pressed
if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) { if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) {
counter = 0; counter = 0;
@ -1203,7 +1203,7 @@ static void processTx(void)
#endif #endif
// push message with 1s timeout // push message with 1s timeout
bool sent = true; bool sent = true;
const uint64_t deadline = AP_HAL::native_micros64() + 1000000; const uint64_t deadline = AP_HAL::micros64() + 1000000;
// try sending to all interfaces // try sending to all interfaces
for (auto &_ins : instances) { for (auto &_ins : instances) {
if (_ins.iface == NULL) { if (_ins.iface == NULL) {
@ -1493,12 +1493,12 @@ static void process1HzTasks(uint64_t timestamp_usec)
#if 0 #if 0
// test code for watchdog reset // test code for watchdog reset
if (AP_HAL::native_millis() > 15000) { if (AP_HAL::millis() > 15000) {
while (true) ; while (true) ;
} }
#endif #endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
if (AP_HAL::native_millis() > 30000) { if (AP_HAL::millis() > 30000) {
// use RTC to mark that we have been running fine for // use RTC to mark that we have been running fine for
// 30s. This is used along with watchdog resets to ensure the // 30s. This is used along with watchdog resets to ensure the
// user has a chance to load a fixed firmware // user has a chance to load a fixed firmware
@ -1518,7 +1518,7 @@ static bool can_do_dna()
return true; return true;
} }
const uint32_t now = AP_HAL::native_millis(); const uint32_t now = AP_HAL::millis();
static uint8_t node_id_allocation_transfer_id = 0; static uint8_t node_id_allocation_transfer_id = 0;
@ -1583,7 +1583,7 @@ void AP_Periph_FW::can_start()
{ {
node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK;
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION; node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION;
node_status.uptime_sec = AP_HAL::native_millis() / 1000U; node_status.uptime_sec = AP_HAL::millis() / 1000U;
if (g.can_node >= 0 && g.can_node < 128) { if (g.can_node >= 0 && g.can_node < 128) {
PreferredNodeID = g.can_node; PreferredNodeID = g.can_node;
@ -1677,7 +1677,7 @@ void AP_Periph_FW::pwm_irq_handler(uint8_t pin, bool pin_state, uint32_t timesta
void AP_Periph_FW::pwm_hardpoint_update() void AP_Periph_FW::pwm_hardpoint_update()
{ {
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
// send at 10Hz // send at 10Hz
void *save = hal.scheduler->disable_interrupts_save(); void *save = hal.scheduler->disable_interrupts_save();
uint16_t value = pwm_hardpoint.highest_pwm; uint16_t value = pwm_hardpoint.highest_pwm;
@ -1821,7 +1821,7 @@ void AP_Periph_FW::apd_esc_telem_update()
void AP_Periph_FW::can_update() void AP_Periph_FW::can_update()
{ {
const uint32_t now = AP_HAL::native_millis(); const uint32_t now = AP_HAL::millis();
const uint32_t led_pattern = 0xAAAA; const uint32_t led_pattern = 0xAAAA;
const uint32_t led_change_period = 50; const uint32_t led_change_period = 50;
static uint8_t led_idx = 0; static uint8_t led_idx = 0;
@ -1849,7 +1849,7 @@ void AP_Periph_FW::can_update()
static uint32_t last_1Hz_ms; static uint32_t last_1Hz_ms;
if (now - last_1Hz_ms >= 1000) { if (now - last_1Hz_ms >= 1000) {
last_1Hz_ms = now; last_1Hz_ms = now;
process1HzTasks(AP_HAL::native_micros64()); process1HzTasks(AP_HAL::micros64());
} }
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
@ -1930,7 +1930,7 @@ void AP_Periph_FW::can_mag_update(void)
#if AP_PERIPH_PROBE_CONTINUOUS #if AP_PERIPH_PROBE_CONTINUOUS
if (compass.get_count() == 0) { if (compass.get_count() == 0) {
static uint32_t last_probe_ms; static uint32_t last_probe_ms;
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
if (now - last_probe_ms >= 1000) { if (now - last_probe_ms >= 1000) {
last_probe_ms = now; last_probe_ms = now;
compass.init(); compass.init();
@ -1971,7 +1971,7 @@ void AP_Periph_FW::can_mag_update(void)
void AP_Periph_FW::can_battery_update(void) void AP_Periph_FW::can_battery_update(void)
{ {
#ifdef HAL_PERIPH_ENABLE_BATTERY #ifdef HAL_PERIPH_ENABLE_BATTERY
const uint32_t now_ms = AP_HAL::native_millis(); const uint32_t now_ms = AP_HAL::millis();
if (now_ms - battery.last_can_send_ms < 100) { if (now_ms - battery.last_can_send_ms < 100) {
return; return;
} }
@ -2372,7 +2372,7 @@ void AP_Periph_FW::can_airspeed_update(void)
} }
#if AP_PERIPH_PROBE_CONTINUOUS #if AP_PERIPH_PROBE_CONTINUOUS
if (!airspeed.healthy()) { if (!airspeed.healthy()) {
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
static uint32_t last_probe_ms; static uint32_t last_probe_ms;
if (now - last_probe_ms >= 1000) { if (now - last_probe_ms >= 1000) {
last_probe_ms = now; last_probe_ms = now;
@ -2380,7 +2380,7 @@ void AP_Periph_FW::can_airspeed_update(void)
} }
} }
#endif #endif
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
if (now - last_airspeed_update_ms < 50) { if (now - last_airspeed_update_ms < 50) {
// max 20Hz data // max 20Hz data
return; return;
@ -2445,7 +2445,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
} }
#if AP_PERIPH_PROBE_CONTINUOUS #if AP_PERIPH_PROBE_CONTINUOUS
if (rangefinder.num_sensors() == 0) { if (rangefinder.num_sensors() == 0) {
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
static uint32_t last_probe_ms; static uint32_t last_probe_ms;
if (now - last_probe_ms >= 1000) { if (now - last_probe_ms >= 1000) {
last_probe_ms = now; last_probe_ms = now;
@ -2453,7 +2453,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
} }
} }
#endif #endif
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
static uint32_t last_update_ms; static uint32_t last_update_ms;
if (g.rangefinder_max_rate > 0 && if (g.rangefinder_max_rate > 0 &&
now - last_update_ms < 1000/g.rangefinder_max_rate) { now - last_update_ms < 1000/g.rangefinder_max_rate) {
@ -2526,7 +2526,7 @@ void AP_Periph_FW::can_proximity_update()
return; return;
} }
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
static uint32_t last_update_ms; static uint32_t last_update_ms;
if (g.proximity_max_rate > 0 && if (g.proximity_max_rate > 0 &&
now - last_update_ms < 1000/g.proximity_max_rate) { now - last_update_ms < 1000/g.proximity_max_rate) {

View File

@ -39,7 +39,7 @@ bool HWESC_Telem::update()
} }
// we expect at least 50ms idle between frames // we expect at least 50ms idle between frames
uint32_t now = AP_HAL::native_millis(); uint32_t now = AP_HAL::millis();
bool frame_gap = (now - last_read_ms) > 10; bool frame_gap = (now - last_read_ms) > 10;
last_read_ms = now; last_read_ms = now;