AC_WPNav: check validity of kP

This commit is contained in:
liang.tang 2018-07-10 14:54:57 +08:00 committed by Randy Mackay
parent bfeeae0e3b
commit 1a12b958fc

View File

@ -386,7 +386,7 @@ bool AC_WPNav::advance_wp_target_along_track(float dt)
// calculate point at which velocity switches from linear to sqrt
float linear_velocity = _wp_speed_cms;
float kP = _pos_control.get_pos_xy_p().kP();
if (kP >= 0.0f) { // avoid divide by zero
if (is_positive(kP)) { // avoid divide by zero
linear_velocity = _track_accel/kP;
}