|
|
@ -197,7 +197,7 @@ void ModeRTL::climb_return_run() |
|
|
|
float target_yaw_rate = 0; |
|
|
|
float target_yaw_rate = 0; |
|
|
|
if (!copter.failsafe.radio) { |
|
|
|
if (!copter.failsafe.radio) { |
|
|
|
// 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)) { |
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
} |
|
|
|
} |
|
|
@ -254,7 +254,7 @@ void ModeRTL::loiterathome_run() |
|
|
|
float target_yaw_rate = 0; |
|
|
|
float target_yaw_rate = 0; |
|
|
|
if (!copter.failsafe.radio) { |
|
|
|
if (!copter.failsafe.radio) { |
|
|
|
// 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)) { |
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
} |
|
|
|
} |
|
|
@ -342,7 +342,7 @@ void ModeRTL::descent_run() |
|
|
|
update_simple_mode(); |
|
|
|
update_simple_mode(); |
|
|
|
|
|
|
|
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max()); |
|
|
|
// 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
|
|
|
|
// 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)) { |
|
|
@ -354,7 +354,7 @@ void ModeRTL::descent_run() |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// 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());
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// set motors to full range
|
|
|
|
// set motors to full range
|
|
|
|