diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 4e900bbb38..78d23e7893 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -101,6 +101,9 @@ public: return pos_control->get_vel_desired_cms(); } + // returns true if pilot's yaw input should be used to adjust vehicle's heading + virtual bool use_pilot_yaw() const {return true; } + protected: // helper functions @@ -394,6 +397,7 @@ public: bool is_landing() const override; bool is_taking_off() const override; + bool use_pilot_yaw() const override; bool requires_terrain_failsafe() const override { return true; } @@ -429,8 +433,6 @@ private: IgnorePilotYaw = (1 << 2U), }; - bool use_pilot_yaw(void) const; - bool start_command(const AP_Mission::Mission_Command& cmd); bool verify_command(const AP_Mission::Mission_Command& cmd); void exit_mission(); @@ -895,6 +897,8 @@ public: // return guided mode timeout in milliseconds. Only used for velocity, acceleration and angle control uint32_t get_timeout_ms() const; + bool use_pilot_yaw() const override; + protected: const char *name() const override { return "GUIDED"; } @@ -932,7 +936,6 @@ private: void velaccel_control_run(); void posvelaccel_control_run(); void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle); - bool use_pilot_yaw(void) const; // controls which controller is run (pos or vel): SubMode guided_mode = SubMode::TakeOff; @@ -1157,6 +1160,8 @@ public: // for reporting to GCS bool get_wp(Location &loc) override; + bool use_pilot_yaw() const override; + // RTL states enum class SubMode : uint8_t { STARTING, @@ -1239,8 +1244,6 @@ private: IgnorePilotYaw = (1U << 2), }; - bool use_pilot_yaw(void) const; - };