diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 98b756a306..86108dc25c 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -202,8 +202,9 @@ void ModeRTL::climb_return_run() float target_yaw_rate = 0; if (!copter.failsafe.radio) { // get pilot's desired yaw rate - if(g.zr_use_rc) + if(g.zr_use_rc){ target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + } if (!is_zero(target_yaw_rate)) { auto_yaw.set_mode(AUTO_YAW_HOLD); } @@ -264,8 +265,9 @@ void ModeRTL::loiterathome_run() float target_yaw_rate = 0; if (!copter.failsafe.radio) { // get pilot's desired yaw rate - if(g.zr_use_rc) + if(g.zr_use_rc){ target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + } if (!is_zero(target_yaw_rate)) { auto_yaw.set_mode(AUTO_YAW_HOLD); } @@ -350,11 +352,11 @@ void ModeRTL::descent_run() update_simple_mode(); // convert pilot input to lean angles - if(g.zr_use_rc) + if(g.zr_use_rc){ get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max()); - + } // record if pilot has overridden roll or pitch - if (!is_zero(target_roll) || !is_zero(target_pitch)) { + if(!is_zero(target_roll) || !is_zero(target_pitch)){ if (!copter.ap.land_repo_active) { copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE); } @@ -363,8 +365,9 @@ void ModeRTL::descent_run() } // get pilot's desired yaw rate - if(g.zr_use_rc) + if(g.zr_use_rc){ target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + } } // set motors to full range diff --git a/modules/mavlink b/modules/mavlink index 72b407db39..6d62818f97 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 72b407db3991ed74631fa59a5e826615f569819f +Subproject commit 6d62818f975c25ffc507904658d8510d3de53c80