From 6c4d988631d911a135f265ff9f2cadbfcacf012c Mon Sep 17 00:00:00 2001 From: Mykhailo Kuznietsov Date: Wed, 11 Oct 2023 18:41:49 +1100 Subject: [PATCH] AC_AttitudeControl: Fix some typos Fixed some typos found in the code. --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 4 ++-- .../AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp | 2 +- libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h | 4 ++-- libraries/AC_AttitudeControl/AC_CommandModel.cpp | 2 +- libraries/AC_AttitudeControl/AC_WeatherVane.cpp | 4 ++-- libraries/AC_AttitudeControl/AC_WeatherVane.h | 2 +- 6 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index b309bbfe16..8d6060d06b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -45,7 +45,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Param: RATE_FF_ENAB // @DisplayName: Rate Feedforward Enable - // @Description: Controls whether body-frame rate feedfoward is enabled or disabled + // @Description: Controls whether body-frame rate feedforward is enabled or disabled // @Values: 0:Disabled, 1:Enabled // @User: Advanced AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT), @@ -785,7 +785,7 @@ void AC_AttitudeControl::thrust_vector_rotation_angles(const Quaternion& attitud // The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame. const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f}; - // attitude_target and attitute_body are passive rotations from target / body frames to the NED frame + // attitude_target and attitude_body are passive rotations from target / body frames to the NED frame // Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame Vector3f att_target_thrust_vec = attitude_target * thrust_vector_up; // target thrust vector diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp index ade5317e2a..c1fe903b69 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp @@ -7,7 +7,7 @@ #include // 6DoF control is extracted from the existing copter code by treating desired angles as thrust angles rather than vehicle attitude. -// Vehicle attitude is then set separately, typically the vehicle would matain 0 roll and pitch. +// Vehicle attitude is then set separately, typically the vehicle would maintain 0 roll and pitch. // rate commands result in the vehicle behaving as a ordinary copter. // run lowest level body-frame rate controller and send outputs to the motors diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h index f089f01d46..8023985eab 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h @@ -20,10 +20,10 @@ public: // Command a Quaternion attitude with feedforward and smoothing // attitude_desired_quat: is updated on each time_step (_dt) by the integral of the angular velocity - // not used anywhere in current code, panic so this implementaiton is not overlooked + // not used anywhere in current code, panic so this implementation is not overlooked void input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_target) override; /* - override input functions to attitude controller and convert desired angles into thrust angles and substitute for osset angles + override input functions to attitude controller and convert desired angles into thrust angles and substitute for offset angles */ // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.cpp b/libraries/AC_AttitudeControl/AC_CommandModel.cpp index 0efe05f36c..caf06d826e 100644 --- a/libraries/AC_AttitudeControl/AC_CommandModel.cpp +++ b/libraries/AC_AttitudeControl/AC_CommandModel.cpp @@ -1,7 +1,7 @@ #include "AC_CommandModel.h" #include -// The Commmand Model class holds parameters that shape the pilot desired angular rate input. This class can +// The Command Model class holds parameters that shape the pilot desired angular rate input. This class can // be expanded to hold the methods that shape the pilot desired input. extern const AP_HAL::HAL& hal; diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp index fd6ad741b3..087f4b2274 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp @@ -23,7 +23,7 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = { // @Param: ENABLE // @DisplayName: Enable - // @Description: Enable weather vaning. When active, the aircraft will automatically yaw into wind when in a VTOL position controlled mode. Pilot yaw commands overide the weathervaning action. + // @Description: Enable weather vaning. When active, the aircraft will automatically yaw into wind when in a VTOL position controlled mode. Pilot yaw commands override the weathervaning action. // @Values: -1:Only use during takeoffs or landing see weathervane takeoff and land override parameters,0:Disabled,1:Nose into wind,2:Nose or tail into wind,3:Side into wind,4:tail into wind // @User: Standard AP_GROUPINFO_FLAGS("ENABLE", 1, AC_WeatherVane, _direction, WVANE_PARAM_ENABLED, AP_PARAM_FLAG_ENABLE), @@ -139,7 +139,7 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con if (is_positive(_max_vel_xy) || is_positive(_max_vel_z)) { Vector3f vel_ned; if (!AP::ahrs().get_velocity_NED(vel_ned) || // need speed estimate - (is_positive(_max_vel_xy) && (vel_ned.xy().length_squared() > (_max_vel_xy*_max_vel_xy))) || // check xy speeed + (is_positive(_max_vel_xy) && (vel_ned.xy().length_squared() > (_max_vel_xy*_max_vel_xy))) || // check xy speed (is_positive(_max_vel_z) && (fabsf(vel_ned.z) > _max_vel_z))) { // check z speed reset(); return false; diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.h b/libraries/AC_AttitudeControl/AC_WeatherVane.h index c4585b21c1..38d7ecb039 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.h +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.h @@ -36,7 +36,7 @@ class AC_WeatherVane { PITCH_ENABLE = (1<<0), }; - // Paramaters + // Parameters AP_Int8 _direction; AP_Float _gain; AP_Float _min_dz_ang_deg;