From e2ed76886cb66da4dbb0a11f58a7397651bdb76c Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Tue, 14 May 2019 17:36:10 +0100 Subject: [PATCH] Rover: AP_MotorsUGV make has sail protected --- APMrover2/AP_MotorsUGV.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/APMrover2/AP_MotorsUGV.h b/APMrover2/AP_MotorsUGV.h index de9a3362a3..5046607d84 100644 --- a/APMrover2/AP_MotorsUGV.h +++ b/APMrover2/AP_MotorsUGV.h @@ -79,9 +79,6 @@ public: // true if vehicle has vectored thrust (i.e. boat with motor on steering servo) bool have_vectored_thrust() const { return is_positive(_vector_throttle_base); } - // true if the vehicle has a mainsail - bool has_sail() const; - // output to motors and steering servos // ground_speed should be the vehicle's speed over the surface in m/s // dt should be expected time between calls to this function @@ -144,6 +141,9 @@ protected: // output for sailboat's mainsail in the range of 0 to 100 void output_mainsail(); + // true if the vehicle has a mainsail + bool has_sail() const; + // slew limit throttle for one iteration void slew_limit_throttle(float dt);