From 793e3da90491d3a9829b15407b70a637ac000c7d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 4 May 2016 21:19:26 +0900 Subject: [PATCH] Copter: rename variables used for NAV_DELAY command --- ArduCopter/Copter.h | 4 ++-- ArduCopter/commands_logic.cpp | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 5a1e3441e7..7d7008dba6 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -380,8 +380,8 @@ private: uint32_t brake_timeout_ms; // Delay the next navigation command - int32_t delay_time_max; // used for delaying the navigation commands (eg land,takeoff etc.) - uint32_t delay_time_start; + int32_t nav_delay_time_max; // used for delaying the navigation commands (eg land,takeoff etc.) + uint32_t nav_delay_time_start; // Flip Vector3f flip_orig_attitude; // original copter attitude before flip diff --git a/ArduCopter/commands_logic.cpp b/ArduCopter/commands_logic.cpp index 06d1d2a2d4..6d13d3cc41 100644 --- a/ArduCopter/commands_logic.cpp +++ b/ArduCopter/commands_logic.cpp @@ -524,16 +524,16 @@ void Copter::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // do_nav_delay - Delay the next navigation command void Copter::do_nav_delay(const AP_Mission::Mission_Command& cmd) { - delay_time_start = millis(); + nav_delay_time_start = millis(); if (cmd.content.nav_delay.seconds > 0) { // relative delay - delay_time_max = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds + nav_delay_time_max = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds } else { // absolute delay to utc time - delay_time_max = hal.util->get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); + nav_delay_time_max = hal.util->get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); } - gcs_send_text_fmt(MAV_SEVERITY_INFO, "Delaying %u sec",(unsigned int)(delay_time_max/1000)); + gcs_send_text_fmt(MAV_SEVERITY_INFO, "Delaying %u sec",(unsigned int)(nav_delay_time_max/1000)); } #if PARACHUTE == ENABLED @@ -762,8 +762,8 @@ bool Copter::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // verify_nav_delay - check if we have waited long enough bool Copter::verify_nav_delay(const AP_Mission::Mission_Command& cmd) { - if (millis() - delay_time_start > (uint32_t)MAX(delay_time_max,0)) { - delay_time_max = 0; + if (millis() - nav_delay_time_start > (uint32_t)MAX(nav_delay_time_max,0)) { + nav_delay_time_max = 0; return true; } return false;