Copter: Add ignore pilot yaw option bit

This commit is contained in:
Gone4Dirt 2021-02-09 08:56:12 +00:00 committed by Randy Mackay
parent 0703a1cf93
commit 1e1be590e2

View File

@ -82,7 +82,7 @@ void ModeSmartRTL::wait_cleanup_run()
void ModeSmartRTL::path_follow_run() void ModeSmartRTL::path_follow_run()
{ {
float target_yaw_rate = 0.0f; float target_yaw_rate = 0.0f;
if (!copter.failsafe.radio) { if (!copter.failsafe.radio && g2.smart_rtl.use_pilot_yaw()) {
// get pilot's desired yaw rate // get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
if (!is_zero(target_yaw_rate)) { if (!is_zero(target_yaw_rate)) {