Skip to content

Commit 67eb20e

Browse files
committed
ArduPlane: fix quadplane stopping speed equation
1 parent 1cdb64b commit 67eb20e

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

ArduPlane/quadplane.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -2530,7 +2530,7 @@ void QuadPlane::vtol_position_controller(void)
25302530
// calculate speed we should be at to reach the position2
25312531
// target speed at the position2 distance threshold, assuming
25322532
// Q_TRANS_DECEL is correct
2533-
const float stopping_speed = safe_sqrt(MAX(0, distance-position2_dist_threshold) * 2 * transition_decel) + position2_target_speed;
2533+
const float stopping_speed = safe_sqrt(MAX(0, distance-position2_dist_threshold) * 2 * transition_decel + sq(position2_target_speed));
25342534

25352535
float target_speed = stopping_speed;
25362536

0 commit comments

Comments
 (0)