From cf96b2d2edb7d319e569631db98358a6299fb8ce Mon Sep 17 00:00:00 2001 From: Mykhailo Kuznietsov Date: Wed, 11 Oct 2023 18:41:50 +1100 Subject: [PATCH] AC_WPNav: Fix some typos Fixed some typos found in the code. --- libraries/AC_WPNav/AC_Circle.cpp | 2 +- libraries/AC_WPNav/AC_Circle.h | 2 +- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 752699a529..ca804a5491 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -174,7 +174,7 @@ bool AC_Circle::update(float climb_rate_cms) _angular_vel = MAX(_angular_vel, _angular_vel_max); } - // update the target angle and total angle traveled + // update the target angle and total angle travelled float angle_change = _angular_vel * dt; _angle += angle_change; _angle = wrap_PI(_angle); diff --git a/libraries/AC_WPNav/AC_Circle.h b/libraries/AC_WPNav/AC_Circle.h index 498241e025..d76fcc90ce 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -153,7 +153,7 @@ private: float _rate; // rotation speed of circle in deg/sec. +ve for cw turn float _yaw; // yaw heading (normally towards circle center) float _angle; // current angular position around circle in radians (0=directly north of the center of the circle) - float _angle_total; // total angle traveled in radians + float _angle_total; // total angle travelled in radians float _angular_vel; // angular velocity in radians/sec float _angular_vel_max; // maximum velocity in radians/sec float _angular_accel; // angular acceleration in radians/sec/sec diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index e63b9fc445..116e85911c 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -482,7 +482,7 @@ bool AC_WPNav::advance_wp_target_along_track(float dt) } // Use vel_scaler_dt to slow down the trajectory time - // vel_scaler_dt scales the velocity and acceleration to be kinematically constent + // vel_scaler_dt scales the velocity and acceleration to be kinematically consistent float vel_scaler_dt = 1.0; if (is_positive(_wp_desired_speed_xy_cms)) { update_vel_accel(_offset_vel, _offset_accel, dt, 0.0, 0.0);