|
|
|
@ -60,7 +60,7 @@ void ModeRTL::run(bool disarm_on_land)
@@ -60,7 +60,7 @@ void ModeRTL::run(bool disarm_on_land)
|
|
|
|
|
break; |
|
|
|
|
case RTL_LoiterAtHome: |
|
|
|
|
// if (rtl_path.land || copter.failsafe.radio) {
|
|
|
|
|
if (g.rtl_alt_final == 0) { |
|
|
|
|
if (g.rtl_alt_final <= 0) { |
|
|
|
|
land_start(); |
|
|
|
|
}else{ |
|
|
|
|
descent_start(); |
|
|
|
@ -192,7 +192,7 @@ void ModeRTL::climb_return_run()
@@ -192,7 +192,7 @@ void ModeRTL::climb_return_run()
|
|
|
|
|
float target_yaw_rate = 0; |
|
|
|
|
if (!copter.failsafe.radio) { |
|
|
|
|
// 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)) { |
|
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
|
} |
|
|
|
@ -249,7 +249,7 @@ void ModeRTL::loiterathome_run()
@@ -249,7 +249,7 @@ void ModeRTL::loiterathome_run()
|
|
|
|
|
float target_yaw_rate = 0; |
|
|
|
|
if (!copter.failsafe.radio) { |
|
|
|
|
// 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)) { |
|
|
|
|
auto_yaw.set_mode(AUTO_YAW_HOLD); |
|
|
|
|
} |
|
|
|
@ -334,7 +334,7 @@ void ModeRTL::descent_run()
@@ -334,7 +334,7 @@ void ModeRTL::descent_run()
|
|
|
|
|
update_simple_mode(); |
|
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|
if (!is_zero(target_roll) || !is_zero(target_pitch)) { |
|
|
|
@ -346,7 +346,7 @@ void ModeRTL::descent_run()
@@ -346,7 +346,7 @@ void ModeRTL::descent_run()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|