AP_Scripting: copter-wall-climber fix for climb rate limiting

This commit is contained in:
Randy Mackay 2020-10-26 16:09:44 +09:00
parent eab7c9520c
commit eb880a2657

View File

@ -202,10 +202,13 @@ function update()
end
-- calculate acceleration limited climb rate
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
-- update target roll using both pilot and autonomous control (+ve right, -ve left)
local roll_speed_target = roll_input * roll_pitch_speed_max + wall_roll_speed