mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: check validity of kP
This commit is contained in:
parent
7e166a4a38
commit
c03e50660c
|
@ -386,7 +386,7 @@ bool AC_WPNav::advance_wp_target_along_track(float dt)
|
||||||
// calculate point at which velocity switches from linear to sqrt
|
// calculate point at which velocity switches from linear to sqrt
|
||||||
float linear_velocity = _wp_speed_cms;
|
float linear_velocity = _wp_speed_cms;
|
||||||
float kP = _pos_control.get_pos_xy_p().kP();
|
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;
|
linear_velocity = _track_accel/kP;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue