mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: copter-wall-climber fix for climb rate limiting
This commit is contained in:
parent
eab7c9520c
commit
eb880a2657
|
@ -202,8 +202,11 @@ function update()
|
|||
end
|
||||
|
||||
-- calculate acceleration limited climb rate
|
||||
climb_rate = math.min(climb_rate_target, climb_rate + climb_rate_chg_max, climb_rate_max)
|
||||
climb_rate = math.max(climb_rate_target, climb_rate - climb_rate_chg_max, -climb_rate_max)
|
||||
if (climb_rate_target >= climb_rate) then
|
||||
climb_rate = math.min(climb_rate_target, climb_rate + climb_rate_chg_max, climb_rate_max)
|
||||
else
|
||||
climb_rate = math.max(climb_rate_target, climb_rate - climb_rate_chg_max, -climb_rate_max)
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
|
|
Loading…
Reference in New Issue