From 551e5fe4dc5447814740b5a8b678e714188e2455 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sat, 7 Aug 2021 16:22:09 +0930 Subject: [PATCH] AC_WPNav: Fix Angle Vel units on function --- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index d80e2007dd..fbd850ce26 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -835,7 +835,7 @@ bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_ void AC_WPNav::calc_scurve_jerk_and_jerk_time() { // calculate jerk - _scurve_jerk = MIN(_attitude_control.get_ang_vel_roll_max_radss() * GRAVITY_MSS, _attitude_control.get_ang_vel_pitch_max_radss() * GRAVITY_MSS); + _scurve_jerk = MIN(_attitude_control.get_ang_vel_roll_max_rads() * GRAVITY_MSS, _attitude_control.get_ang_vel_pitch_max_rads() * GRAVITY_MSS); if (is_zero(_scurve_jerk)) { _scurve_jerk = _wp_jerk; } else {