mirror of https://github.com/ArduPilot/ardupilot
Copter: avoid ascend beyond fence's max alt in circle mode
This commit is contained in:
parent
a626c467c2
commit
e3b613ac65
|
@ -90,6 +90,9 @@ void ModeCircle::run()
|
|||
// get pilot desired climb rate (or zero if in radio failsafe)
|
||||
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
|
||||
|
||||
// get avoidance adjusted climb rate
|
||||
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
|
||||
|
||||
// if not armed set throttle to zero and exit immediately
|
||||
if (is_disarmed_or_landed()) {
|
||||
make_safe_ground_handling();
|
||||
|
|
Loading…
Reference in New Issue