mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: Fix Angle Vel units on function
This commit is contained in:
parent
0ee9dbc059
commit
8cd70f2569
|
@ -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()
|
void AC_WPNav::calc_scurve_jerk_and_jerk_time()
|
||||||
{
|
{
|
||||||
// calculate jerk
|
// 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)) {
|
if (is_zero(_scurve_jerk)) {
|
||||||
_scurve_jerk = _wp_jerk;
|
_scurve_jerk = _wp_jerk;
|
||||||
} else {
|
} else {
|
||||||
|
|
Loading…
Reference in New Issue