From 43449a4adb9d6b1f2b58e7aec47d0743c17c3f72 Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Sat, 7 Sep 2019 23:18:13 +0100 Subject: [PATCH] AR_WPNav: remove unneeded overshoot methods --- libraries/AR_WPNav/AR_WPNav.cpp | 6 ------ libraries/AR_WPNav/AR_WPNav.h | 4 ---- 2 files changed, 10 deletions(-) diff --git a/libraries/AR_WPNav/AR_WPNav.cpp b/libraries/AR_WPNav/AR_WPNav.cpp index f98b5a9e06..750c5b380d 100644 --- a/libraries/AR_WPNav/AR_WPNav.cpp +++ b/libraries/AR_WPNav/AR_WPNav.cpp @@ -424,12 +424,6 @@ void AR_WPNav::set_turn_params(float turn_max_g, float turn_radius, bool pivot_p _pivot_possible = pivot_possible; } -// set default overshoot (used for sailboats) -void AR_WPNav::set_default_overshoot(float overshoot) -{ - _overshoot.set_default(overshoot); -} - // adjust speed to ensure it does not fall below value held in SPEED_MIN void AR_WPNav::apply_speed_min(float &desired_speed) { diff --git a/libraries/AR_WPNav/AR_WPNav.h b/libraries/AR_WPNav/AR_WPNav.h index db1532adf7..a84838daef 100644 --- a/libraries/AR_WPNav/AR_WPNav.h +++ b/libraries/AR_WPNav/AR_WPNav.h @@ -72,13 +72,9 @@ public: // settor to allow vehicle code to provide turn related param values to this library (should be updated regularly) void set_turn_params(float turn_max_g, float turn_radius, bool pivot_possible); - // set default overshoot (used for sailboats) - void set_default_overshoot(float overshoot); - // accessors for parameter values float get_default_speed() const { return _speed_max; } float get_radius() const { return _radius; } - float get_overshoot() const { return _overshoot; } float get_pivot_rate() const { return _pivot_rate; } // calculate stopping location using current position and attitude controller provided maximum deceleration