diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 78d23e7893..9509bb32cf 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1266,6 +1266,7 @@ public: void exit() override; bool is_landing() const override; + bool use_pilot_yaw() const override; // Safe RTL states enum class SubMode : uint8_t { diff --git a/ArduCopter/mode_smart_rtl.cpp b/ArduCopter/mode_smart_rtl.cpp index 656a91932c..206da2f7d9 100644 --- a/ArduCopter/mode_smart_rtl.cpp +++ b/ArduCopter/mode_smart_rtl.cpp @@ -82,7 +82,7 @@ void ModeSmartRTL::wait_cleanup_run() void ModeSmartRTL::path_follow_run() { float target_yaw_rate = 0.0f; - if (!copter.failsafe.radio && g2.smart_rtl.use_pilot_yaw()) { + if (!copter.failsafe.radio && use_pilot_yaw()) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { @@ -207,4 +207,9 @@ int32_t ModeSmartRTL::wp_bearing() const return wp_nav->get_wp_bearing_to_destination(); } +bool ModeSmartRTL::use_pilot_yaw() const +{ + return g2.smart_rtl.use_pilot_yaw(); +} + #endif