From db2229f6847f73f1d949159ec63f63db0cd637d7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 7 Mar 2020 11:28:43 +0900 Subject: [PATCH] Copter: ModeGuided::do_user_takeoff_start arg rename this makes it more consistent with the method it is overriding --- ArduCopter/mode.h | 2 +- ArduCopter/mode_guided.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 614ba0d7c9..60d291b7db 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -796,7 +796,7 @@ public: bool is_taking_off() const override; - bool do_user_takeoff_start(float final_alt_above_home) override; + bool do_user_takeoff_start(float takeoff_alt_cm) override; GuidedMode mode() const { return guided_mode; } diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 27aca8adf5..3787b4959b 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -47,13 +47,13 @@ bool ModeGuided::init(bool ignore_checks) // do_user_takeoff_start - initialises waypoint controller to implement take-off -bool ModeGuided::do_user_takeoff_start(float final_alt_above_home) +bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm) { guided_mode = Guided_TakeOff; // initialise wpnav destination Location target_loc = copter.current_loc; - target_loc.set_alt_cm(final_alt_above_home, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_cm(takeoff_alt_cm, Location::AltFrame::ABOVE_HOME); if (!wp_nav->set_wp_destination(target_loc)) { // failure to set destination can only be because of missing terrain data