diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index c8d68f6765..828f57798c 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -133,7 +133,7 @@ float Sub::get_surface_tracking_climb_rate(int16_t target_rate, float current_al float velocity_correction; float current_alt = inertial_nav.get_altitude(); - uint32_t now = millis(); + uint32_t now = AP_HAL::millis(); // reset target altitude if this controller has just been engaged if (now - last_call_ms > RANGEFINDER_TIMEOUT_MS) { diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 6e605edd0e..f0c6ec6578 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1285,7 +1285,7 @@ void Sub::mavlink_delay_cb() DataFlash.EnableWrites(false); - uint32_t tnow = millis(); + uint32_t tnow = AP_HAL::millis(); if (tnow - last_1hz > 1000) { last_1hz = tnow; gcs_send_heartbeat(); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 0761e89415..f55fe94e93 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -724,5 +724,4 @@ public: extern const AP_HAL::HAL& hal; extern Sub sub; -using AP_HAL::millis; using AP_HAL::micros; diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index 1a4e0358fe..691fc6d3ca 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -519,7 +519,7 @@ void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // do_nav_delay - Delay the next navigation command void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd) { - nav_delay_time_start = millis(); + nav_delay_time_start = AP_HAL::millis(); if (cmd.content.nav_delay.seconds > 0) { // relative delay @@ -580,11 +580,11 @@ bool Sub::verify_nav_wp(const AP_Mission::Mission_Command& cmd) // start timer if necessary if (loiter_time == 0) { - loiter_time = millis(); + loiter_time = AP_HAL::millis(); } // check if timer has run out - if (((millis() - loiter_time) / 1000) >= loiter_time_max) { + if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) { gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index); return true; } @@ -648,11 +648,11 @@ bool Sub::verify_loiter_time() // start our loiter timer if (loiter_time == 0) { - loiter_time = millis(); + loiter_time = AP_HAL::millis(); } // check if loiter timer has run out - return (((millis() - loiter_time) / 1000) >= loiter_time_max); + return (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max); } // verify_circle - check if we have circled the point enough @@ -695,11 +695,11 @@ bool Sub::verify_spline_wp(const AP_Mission::Mission_Command& cmd) // start timer if necessary if (loiter_time == 0) { - loiter_time = millis(); + loiter_time = AP_HAL::millis(); } // check if timer has run out - if (((millis() - loiter_time) / 1000) >= loiter_time_max) { + if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) { gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index); return true; } @@ -724,7 +724,7 @@ bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // verify_nav_delay - check if we have waited long enough bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd) { - if (millis() - nav_delay_time_start > (uint32_t)MAX(nav_delay_time_max,0)) { + if (AP_HAL::millis() - nav_delay_time_start > (uint32_t)MAX(nav_delay_time_max, 0)) { nav_delay_time_max = 0; return true; } @@ -737,7 +737,7 @@ bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd) void Sub::do_wait_delay(const AP_Mission::Mission_Command& cmd) { - condition_start = millis(); + condition_start = AP_HAL::millis(); condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds } @@ -762,7 +762,7 @@ void Sub::do_yaw(const AP_Mission::Mission_Command& cmd) bool Sub::verify_wait_delay() { - if (millis() - condition_start > (uint32_t)MAX(condition_value,0)) { + if (AP_HAL::millis() - condition_start > (uint32_t)MAX(condition_value, 0)) { condition_value = 0; return true; } diff --git a/ArduSub/control_guided.cpp b/ArduSub/control_guided.cpp index 0edf56ea57..f2562424bd 100644 --- a/ArduSub/control_guided.cpp +++ b/ArduSub/control_guided.cpp @@ -125,7 +125,7 @@ void Sub::guided_angle_control_start() pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); // initialise targets - guided_angle_state.update_time_ms = millis(); + guided_angle_state.update_time_ms = AP_HAL::millis(); guided_angle_state.roll_cd = ahrs.roll_sensor; guided_angle_state.pitch_cd = ahrs.pitch_sensor; guided_angle_state.yaw_cd = ahrs.yaw_sensor; @@ -203,7 +203,7 @@ void Sub::guided_set_velocity(const Vector3f& velocity) guided_vel_control_start(); } - vel_update_time_ms = millis(); + vel_update_time_ms = AP_HAL::millis(); // set position controller velocity target pos_control.set_desired_velocity(velocity); @@ -227,7 +227,7 @@ bool Sub::guided_set_destination_posvel(const Vector3f& destination, const Vecto } #endif - posvel_update_time_ms = millis(); + posvel_update_time_ms = AP_HAL::millis(); posvel_pos_target_cm = destination; posvel_vel_target_cms = velocity; @@ -253,7 +253,7 @@ void Sub::guided_set_angle(const Quaternion &q, float climb_rate_cms) guided_angle_state.yaw_cd = wrap_180_cd(ToDeg(guided_angle_state.yaw_cd) * 100.0f); guided_angle_state.climb_rate_cms = climb_rate_cms; - guided_angle_state.update_time_ms = millis(); + guided_angle_state.update_time_ms = AP_HAL::millis(); } // guided_run - runs the guided controller @@ -363,7 +363,7 @@ void Sub::guided_vel_control_run() motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // set velocity to zero if no updates received for 3 seconds - uint32_t tnow = millis(); + uint32_t tnow = AP_HAL::millis(); if (tnow - vel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !pos_control.get_desired_velocity().is_zero()) { pos_control.set_desired_velocity(Vector3f(0,0,0)); } @@ -419,7 +419,7 @@ void Sub::guided_posvel_control_run() motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // set velocity to zero if no updates received for 3 seconds - uint32_t tnow = millis(); + uint32_t tnow = AP_HAL::millis(); if (tnow - posvel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !posvel_vel_target_cms.is_zero()) { posvel_vel_target_cms.zero(); } @@ -493,7 +493,7 @@ void Sub::guided_angle_control_run() float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -fabsf(wp_nav.get_speed_down()), wp_nav.get_speed_up()); // check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds - uint32_t tnow = millis(); + uint32_t tnow = AP_HAL::millis(); if (tnow - guided_angle_state.update_time_ms > GUIDED_ATTITUDE_TIMEOUT_MS) { roll_in = 0.0f; pitch_in = 0.0f; @@ -547,7 +547,7 @@ void Sub::guided_limit_init_time_and_pos() bool Sub::guided_limit_check() { // check if we have passed the timeout - if ((guided_limit.timeout_ms > 0) && (millis() - guided_limit.start_time >= guided_limit.timeout_ms)) { + if ((guided_limit.timeout_ms > 0) && (AP_HAL::millis() - guided_limit.start_time >= guided_limit.timeout_ms)) { return true; } diff --git a/ArduSub/failsafe.cpp b/ArduSub/failsafe.cpp index 20b63a4739..79acf48873 100644 --- a/ArduSub/failsafe.cpp +++ b/ArduSub/failsafe.cpp @@ -441,7 +441,7 @@ void Sub::failsafe_terrain_check() // set terrain data status (found or not found) void Sub::failsafe_terrain_set_status(bool data_ok) { - uint32_t now = millis(); + uint32_t now = AP_HAL::millis(); // record time of first and latest failures (i.e. duration of failures) if (!data_ok) {