From 85977910ea2d00ae0cc4a381d5e63ca3c40b91a7 Mon Sep 17 00:00:00 2001 From: Mykhailo Kuznietsov Date: Sun, 8 Oct 2023 21:38:43 +0300 Subject: [PATCH] Fix some typos Most are typos, but some words changed to en-GB version. --- AntennaTracker/AntennaTracker.txt | 4 ++-- AntennaTracker/GCS_Mavlink.h | 2 +- AntennaTracker/Parameters.cpp | 2 +- ArduCopter/AP_ExternalControl_Copter.cpp | 2 +- ArduCopter/crash_check.cpp | 4 ++-- ArduCopter/mode_autorotate.cpp | 4 ++-- ArduCopter/mode_systemid.cpp | 2 +- ArduPlane/Attitude.cpp | 10 +++++----- ArduPlane/Parameters.cpp | 2 +- ArduPlane/Parameters.h | 4 ++-- ArduPlane/Plane.h | 8 ++++---- ArduPlane/ReleaseNotes.txt | 2 +- ArduPlane/ekf_check.cpp | 4 ++-- ArduPlane/events.cpp | 4 ++-- ArduPlane/is_flying.cpp | 2 +- ArduPlane/mode_acro.cpp | 2 +- ArduPlane/mode_qacro.cpp | 2 +- ArduPlane/mode_qrtl.cpp | 2 +- ArduPlane/mode_qstabilize.cpp | 2 +- ArduPlane/motor_test.cpp | 2 +- ArduPlane/navigation.cpp | 4 ++-- ArduPlane/quadplane.cpp | 4 ++-- ArduPlane/servos.cpp | 2 +- ArduPlane/system.cpp | 2 +- ArduPlane/tailsitter.cpp | 14 +++++++------- ArduPlane/takeoff.cpp | 2 +- ArduPlane/tiltrotor.cpp | 6 +++--- ArduSub/Parameters.h | 2 +- ArduSub/ReleaseNotes.txt | 2 +- ArduSub/defines.h | 2 +- ArduSub/mode_poshold.cpp | 2 +- Blimp/Blimp.h | 2 +- Blimp/Fins.h | 2 +- .../AC_AttitudeControl/AC_AttitudeControl.cpp | 4 ++-- .../AC_AttitudeControl_Multi_6DoF.cpp | 2 +- .../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 +- libraries/AC_AutoTune/AC_AutoTune.h | 2 +- libraries/AC_AutoTune/AC_AutoTune_Heli.cpp | 8 ++++---- libraries/AC_AutoTune/AC_AutoTune_Heli.h | 8 ++++---- libraries/AC_AutoTune/AC_AutoTune_Multi.cpp | 2 +- libraries/AC_AutoTune/AC_AutoTune_Multi.h | 6 +++--- libraries/AC_Autorotation/AC_Autorotation.cpp | 8 ++++---- libraries/AC_Autorotation/AC_Autorotation.h | 2 +- libraries/AC_Avoidance/AC_Avoid.cpp | 6 +++--- libraries/AC_Avoidance/AC_Avoid.h | 4 ++-- libraries/AC_Avoidance/AP_OABendyRuler.h | 2 +- libraries/AC_Avoidance/AP_OADatabase.cpp | 2 +- libraries/AC_Avoidance/AP_OADijkstra.cpp | 2 +- libraries/AC_Avoidance/AP_OADijkstra.h | 2 +- libraries/AC_CustomControl/AC_CustomControl.h | 2 +- .../AC_CustomControl/AC_CustomControl_Empty.cpp | 8 ++++---- libraries/AC_Fence/AC_Fence.cpp | 2 +- libraries/AC_Fence/AC_PolyFence_loader.h | 6 +++--- libraries/AC_PID/AC_PI_2D.h | 2 +- .../AC_PID/examples/AC_PID_test/AC_PID_test.cpp | 2 +- libraries/AC_PrecLand/AC_PrecLand.cpp | 6 +++--- libraries/AC_PrecLand/AC_PrecLand.h | 2 +- .../AC_PrecLand/AC_PrecLand_StateMachine.cpp | 8 ++++---- libraries/AC_PrecLand/AC_PrecLand_StateMachine.h | 4 ++-- libraries/AC_Sprayer/AC_Sprayer.cpp | 4 ++-- libraries/AC_WPNav/AC_Circle.cpp | 2 +- libraries/AC_WPNav/AC_Circle.h | 2 +- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- libraries/AP_ADSB/AP_ADSB.cpp | 2 +- libraries/AP_ADSB/AP_ADSB.h | 2 +- libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp | 2 +- libraries/AP_AHRS/AP_AHRS.cpp | 16 ++++++++-------- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 14 +++++++------- libraries/AP_AHRS/AP_AHRS_DCM.h | 2 +- libraries/AP_AIS/AP_AIS.cpp | 10 +++++----- libraries/AP_AIS/AP_AIS.h | 2 +- libraries/AP_AccelCal/AccelCalibrator.cpp | 10 +++++----- libraries/AP_AccelCal/AccelCalibrator.h | 2 +- libraries/AP_Airspeed/AP_Airspeed.cpp | 4 ++-- libraries/AP_Airspeed/AP_Airspeed.h | 2 +- libraries/AP_Airspeed/AP_Airspeed_Backend.h | 2 +- libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp | 2 +- libraries/AP_Arming/AP_Arming.cpp | 2 +- libraries/AP_BLHeli/AP_BLHeli.cpp | 6 +++--- libraries/AP_BLHeli/AP_BLHeli.h | 2 +- libraries/AP_Baro/AP_Baro.cpp | 4 ++-- libraries/AP_Baro/AP_Baro.h | 2 +- libraries/AP_Baro/AP_Baro_BMP085.cpp | 4 ++-- libraries/AP_Baro/AP_Baro_BMP280.cpp | 2 +- libraries/AP_Baro/AP_Baro_BMP388.cpp | 2 +- libraries/AP_Baro/AP_Baro_Backend.cpp | 2 +- libraries/AP_Baro/AP_Baro_Backend.h | 2 +- libraries/AP_Baro/AP_Baro_DPS280.cpp | 2 +- libraries/AP_Baro/AP_Baro_DroneCAN.cpp | 2 +- libraries/AP_Baro/AP_Baro_FBM320.cpp | 2 +- libraries/AP_Baro/AP_Baro_LPS2XH.cpp | 2 +- libraries/AP_Baro/AP_Baro_SPL06.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 2 +- .../AP_BattMonitor/AP_BattMonitor_Bebop.cpp | 2 +- .../AP_BattMonitor/AP_BattMonitor_Generator.cpp | 4 ++-- .../AP_BattMonitor/AP_BattMonitor_Generator.h | 2 +- .../AP_BattMonitor_SMBus_Generic.cpp | 2 +- .../AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp | 4 ++-- .../AP_BattMonitor_Synthetic_Current.h | 2 +- libraries/AP_Beacon/AP_Beacon_Nooploop.h | 2 +- libraries/AP_BoardConfig/AP_BoardConfig.cpp | 2 +- libraries/AP_CANManager/AP_CANManager.cpp | 2 +- libraries/AP_CANManager/AP_CANSensor.cpp | 2 +- libraries/AP_CANManager/AP_SLCANIface.cpp | 2 +- libraries/AP_Camera/AP_Camera_SoloGimbal.cpp | 2 +- libraries/AP_Camera/AP_RunCam.cpp | 6 +++--- libraries/AP_Common/Location.cpp | 2 +- libraries/AP_Common/Location.h | 2 +- libraries/AP_Common/tests/test_location.cpp | 2 +- libraries/AP_Common/tests/test_nmea_print.cpp | 2 +- libraries/AP_Compass/AP_Compass_Backend.cpp | 6 +++--- libraries/AP_Compass/AP_Compass_Backend.h | 2 +- libraries/AP_Compass/AP_Compass_Calibration.cpp | 4 ++-- libraries/AP_Compass/AP_Compass_DroneCAN.cpp | 4 ++-- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 2 +- libraries/AP_Compass/AP_Compass_MMC5xx3.cpp | 2 +- libraries/AP_Compass/AP_Compass_SITL.cpp | 2 +- libraries/AP_Compass/CompassCalibrator.h | 2 +- libraries/AP_DAL/AP_DAL.cpp | 12 ++++++------ libraries/AP_DAL/AP_DAL.h | 2 +- libraries/AP_DDS/AP_DDS_Client.cpp | 4 ++-- libraries/AP_DDS/AP_DDS_External_Odom.cpp | 4 ++-- libraries/AP_DDS/README.md | 8 ++++---- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 2 +- libraries/AP_EFI/AP_EFI_Serial_MS.cpp | 2 +- libraries/AP_ESC_Telem/AP_ESC_Telem.h | 2 +- libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp | 2 +- libraries/AP_ExternalAHRS/AP_ExternalAHRS.h | 2 +- .../AP_ExternalAHRS_MicroStrain5.cpp | 2 +- .../AP_ExternalAHRS_MicroStrain5.h | 2 +- .../AP_ExternalAHRS_VectorNav.cpp | 6 +++--- .../AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h | 2 +- libraries/AP_ExternalAHRS/MicroStrain_common.cpp | 2 +- libraries/AP_ExternalAHRS/MicroStrain_common.h | 2 +- libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp | 2 +- .../examples/jedec_test/jedec_test.cpp | 2 +- libraries/AP_FlashStorage/AP_FlashStorage.cpp | 2 +- libraries/AP_FlashStorage/AP_FlashStorage.h | 2 +- libraries/AP_Follow/AP_Follow.cpp | 2 +- libraries/AP_Frsky_Telem/AP_Frsky_D.cpp | 4 ++-- .../AP_Frsky_MAVlite_SPortToMAVlite.cpp | 2 +- libraries/AP_GPS/AP_GPS.cpp | 6 +++--- libraries/AP_GPS/AP_GPS_DroneCAN.cpp | 2 +- libraries/AP_GPS/AP_GPS_NMEA.cpp | 2 +- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 2 +- libraries/AP_GPS/GPS_Backend.cpp | 6 +++--- libraries/AP_Generator/AP_Generator.cpp | 6 +++--- libraries/AP_Generator/AP_Generator_Backend.cpp | 2 +- libraries/AP_Generator/AP_Generator_IE_650_800.h | 4 ++-- .../AP_Generator/AP_Generator_IE_FuelCell.h | 2 +- .../AP_Generator/AP_Generator_RichenPower.cpp | 2 +- libraries/AP_Gripper/AP_Gripper.h | 2 +- libraries/AP_Gripper/AP_Gripper_Backend.h | 2 +- libraries/AP_Gripper/AP_Gripper_Servo.h | 2 +- libraries/AP_GyroFFT/AP_GyroFFT.cpp | 4 ++-- libraries/AP_GyroFFT/AP_GyroFFT.h | 2 +- libraries/AP_HAL/AP_HAL_Boards.h | 2 +- libraries/AP_HAL/AP_HAL_Namespace.h | 2 +- libraries/AP_HAL/CANIface.h | 6 +++--- libraries/AP_HAL/Device.cpp | 2 +- libraries/AP_HAL/GPIO.h | 2 +- libraries/AP_HAL/RCOutput.h | 2 +- libraries/AP_HAL/WSPIDevice.h | 2 +- libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp | 2 +- libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp | 6 +++--- libraries/AP_HAL/examples/Storage/Storage.cpp | 4 ++-- libraries/AP_HAL/utility/ftoa_engine.cpp | 2 +- libraries/AP_HAL/utility/srxl.cpp | 4 ++-- libraries/AP_HAL/utility/st24.cpp | 2 +- libraries/AP_HAL/utility/sumd.h | 2 +- 174 files changed, 287 insertions(+), 287 deletions(-) diff --git a/AntennaTracker/AntennaTracker.txt b/AntennaTracker/AntennaTracker.txt index f66169dee5093a..8ced3605b22465 100644 --- a/AntennaTracker/AntennaTracker.txt +++ b/AntennaTracker/AntennaTracker.txt @@ -109,7 +109,7 @@ around. It might even damage itself. AntennaTracker (like other ardupilot software such as ArduPlane, ArduRover etc) has configuration values that control and tailor its operation, and which are stored in EEPROM on the processor. The configuration is restored from -EEPROM every time the processsor starts. +EEPROM every time the processor starts. You can use MissionPlanner, mavproxy or apm_planner or other mavlink compatible software to check and change the configuration of your AntennaTracker. @@ -219,7 +219,7 @@ the vehicle, cd to the ArduPlane directory and run this: ../Tools/autotest/sim_arduplane.sh -T --aircraft test -The -T flag tells sim_arduplane.sh to start an entenna tracker +The -T flag tells sim_arduplane.sh to start an antenna tracker simulator and also start a virtual antenna tracker in a window. To start the antenna tracker running run "tracker start" in the diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index 84313915464f42..38f7cdb483e712 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -14,7 +14,7 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK protected: // telem_delay is not used by Tracker but is pure virtual, thus - // this implementaiton. it probably *should* be used by Tracker, + // this implementation. it probably *should* be used by Tracker, // as currently Tracker may brick XBees uint32_t telem_delay() const override { return 0; } diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 40b22e682eec3a..e1757fba32e4cf 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -130,7 +130,7 @@ const AP_Param::Info Tracker::var_info[] = { // @Param: ONOFF_PITCH_MINT // @DisplayName: Pitch minimum movement time - // @Description: Minimim amount of time in seconds to move in pitch + // @Description: Minimum amount of time in seconds to move in pitch // @Units: s // @Increment: 0.01 // @Range: 0 2 diff --git a/ArduCopter/AP_ExternalControl_Copter.cpp b/ArduCopter/AP_ExternalControl_Copter.cpp index e5f1f49ec74213..35353a412618f6 100644 --- a/ArduCopter/AP_ExternalControl_Copter.cpp +++ b/ArduCopter/AP_ExternalControl_Copter.cpp @@ -19,7 +19,7 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f } const float yaw_rate_cds = isnan(yaw_rate_rads)? 0: degrees(yaw_rate_rads)*100; - // Copter velocity is positive if aicraft is moving up which is opposite the incoming NED frame. + // Copter velocity is positive if aircraft is moving up which is opposite the incoming NED frame. Vector3f velocity_NEU_ms { linear_velocity.x, linear_velocity.y, diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 18a04aec4fdf8d..786e56b5a0e522 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -101,7 +101,7 @@ void Copter::thrust_loss_check() { static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed - // no-op if suppresed by flight options param + // no-op if suppressed by flight options param if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_THRUST_LOSS_CHECK)) != 0) { return; } @@ -181,7 +181,7 @@ void Copter::thrust_loss_check() // check for a large yaw imbalance, could be due to badly calibrated ESC or misaligned motors void Copter::yaw_imbalance_check() { - // no-op if suppresed by flight options param + // no-op if suppressed by flight options param if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_YAW_IMBALANCE_WARNING)) != 0) { return; } diff --git a/ArduCopter/mode_autorotate.cpp b/ArduCopter/mode_autorotate.cpp index fb009a1d3421d7..414401c2e9a571 100644 --- a/ArduCopter/mode_autorotate.cpp +++ b/ArduCopter/mode_autorotate.cpp @@ -47,7 +47,7 @@ bool ModeAutorotate::init(bool ignore_checks) // Display message gcs().send_text(MAV_SEVERITY_INFO, "Autorotation initiated"); - // Set all inial flags to on + // Set all intial flags to on _flags.entry_initial = 1; _flags.ss_glide_initial = 1; _flags.flare_initial = 1; @@ -173,7 +173,7 @@ void ModeAutorotate::run() g2.arot.set_desired_fwd_speed(); // Set target head speed in head speed controller - _target_head_speed = HEAD_SPEED_TARGET_RATIO; //Ensure target hs is set to glide in case hs hasent reached target for glide + _target_head_speed = HEAD_SPEED_TARGET_RATIO; //Ensure target hs is set to glide in case hs has not reached target for glide g2.arot.set_target_head_speed(_target_head_speed); // Prevent running the initial glide functions again diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 50fe12749df3d4..15dc1eba4f0ede 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -107,7 +107,7 @@ bool ModeSystemId::init(bool ignore_checks) // systemId_exit - clean up systemId controller before exiting void ModeSystemId::exit() { - // reset the feedfoward enabled parameter to the initialized state + // reset the feedforward enabled parameter to the initialized state attitude_control->bf_feedforward(att_bf_feedforward); } diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 9bba585d0f7030..39a9461ea63e7d 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -32,7 +32,7 @@ float Plane::calc_speed_scaler(void) speed_scaler = MIN(speed_scaler, new_scaler); // we also decay the integrator to prevent an integrator from before - // we were at low speed persistint at high speed + // we were at low speed persistent at high speed rollController.decay_I(); pitchController.decay_I(); yawController.decay_I(); @@ -51,7 +51,7 @@ float Plane::calc_speed_scaler(void) } if (!plane.ahrs.airspeed_sensor_enabled() && (plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) && - (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is surpressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates + (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is suppressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates return MIN(speed_scaler, 1.0f) ; } return speed_scaler; @@ -486,7 +486,7 @@ int16_t Plane::calc_nav_yaw_coordinated() // user is doing an AUTOTUNE with yaw rate control const float rudd_expo = rudder_in_expo(true); const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate; - // add in the corrdinated turn yaw rate to make it easier to fly while tuning the yaw rate controller + // add in the coordinated turn yaw rate to make it easier to fly while tuning the yaw rate controller const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(radians(nav_roll_cd*0.01f))/MAX(aparm.airspeed_min,smoothed_airspeed)); commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false); using_rate_controller = true; @@ -658,11 +658,11 @@ void Plane::update_load_factor(void) nav_roll_cd = constrain_int32(nav_roll_cd, -2500, 2500); roll_limit_cd = MIN(roll_limit_cd, 2500); } else if (max_load_factor < aerodynamic_load_factor) { - // the demanded nav_roll would take us past the aerodymamic + // the demanded nav_roll would take us past the aerodynamic // load limit. Limit our roll to a bank angle that will keep // the load within what the airframe can handle. We always // allow at least 25 degrees of roll however, to ensure the - // aircraft can be maneuvered with a bad airspeed estimate. At + // aircraft can be manoeuvred with a bad airspeed estimate. At // 25 degrees the load factor is 1.1 (10%) int32_t roll_limit = degrees(acosf(sq(1.0f / max_load_factor)))*100; if (roll_limit < 2500) { diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index b0cddc9081358d..720eed4c273694 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -159,7 +159,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: TKOFF_TDRAG_SPD1 // @DisplayName: Takeoff tail dragger speed1 - // @Description: This parameter sets the airspeed at which to stop holding the tail down and transition to rudder control of steering on the ground. When TKOFF_TDRAG_SPD1 is reached the pitch of the aircraft will be held level until TKOFF_ROTATE_SPD is reached, at which point the takeoff pitch specified in the mission will be used to "rotate" the pitch for takeoff climb. Set TKOFF_TDRAG_SPD1 to zero to go straight to rotation. This should be set to zero for hand launch and catapult launch. It should also be set to zero for tricycle undercarriages unless you are using the method above to genetly hold the nose wheel down. For tail dragger aircraft it should be set just below the stall speed. + // @Description: This parameter sets the airspeed at which to stop holding the tail down and transition to rudder control of steering on the ground. When TKOFF_TDRAG_SPD1 is reached the pitch of the aircraft will be held level until TKOFF_ROTATE_SPD is reached, at which point the takeoff pitch specified in the mission will be used to "rotate" the pitch for takeoff climb. Set TKOFF_TDRAG_SPD1 to zero to go straight to rotation. This should be set to zero for hand launch and catapult launch. It should also be set to zero for tricycle undercarriages unless you are using the method above to gently hold the nose wheel down. For tail dragger aircraft it should be set just below the stall speed. // @Units: m/s // @Range: 0 30 // @Increment: 0.1 diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index e9c25ea5da1746..7210bfe7771267 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -421,7 +421,7 @@ class Parameters { AP_Int8 flight_mode6; AP_Int8 initial_mode; - // Navigational maneuvering limits + // Navigational manoeuvring limits // AP_Int16 alt_offset; AP_Int16 acro_roll_rate; @@ -541,7 +541,7 @@ class ParametersG2 { AP_Int8 crow_flap_options; AP_Int8 crow_flap_aileron_matching; - // Forward throttle battery voltage compenstaion + // Forward throttle battery voltage compensation AP_Float fwd_thr_batt_voltage_max; AP_Float fwd_thr_batt_voltage_min; AP_Int8 fwd_thr_batt_idx; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 9634184c830789..fe8a935dc7c748 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -246,7 +246,7 @@ class Plane : public AP_Vehicle { #endif #if HAL_RALLY_ENABLED - // Rally Ponints + // Rally Points AP_Rally rally; #endif @@ -312,7 +312,7 @@ class Plane : public AP_Vehicle { // Failsafe struct { - // Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold + // Used to track if the value on channel 3 (throttle) has fallen below the failsafe threshold // RC receiver should be set up to output a low throttle value when signal is lost bool rc_failsafe; @@ -618,7 +618,7 @@ class Plane : public AP_Vehicle { // The instantaneous desired pitch angle. Hundredths of a degree int32_t nav_pitch_cd; - // the aerodymamic load factor. This is calculated from the demanded + // the aerodynamic load factor. This is calculated from the demanded // roll before the roll is clipped, using 1/sqrt(cos(nav_roll)) float aerodynamic_load_factor = 1.0f; @@ -771,7 +771,7 @@ class Plane : public AP_Vehicle { AP_Mount camera_mount; #endif - // Arming/Disarming mangement class + // Arming/Disarming management class AP_Arming_Plane arming; AP_Param param_loader {var_info}; diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index bf2b93000972c7..aea5447a21c41d 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -284,7 +284,7 @@ of changes. Many thanks to all the people who have contributed! - Gimbal/Mount2 can be moved to retracted or neutral position - Gremsy ZIO support - IMAGE_START_CAPTURE, SET_CAMERA_ZOOM/FOCUS, VIDEO_START/STOP_CAPTURE command support - - Paramters renamed and rescaled + - Parameters renamed and rescaled i) CAM_TRIGG_TYPE renamed to CAM1_TYPE and options have changed ii) CAM_DURATION renamed to CAM1_DURATION and scaled in seconds iii) CAM_FEEDBACK_PIN/POL renamed to CAM1_FEEBAK_PIN/POL diff --git a/ArduPlane/ekf_check.cpp b/ArduPlane/ekf_check.cpp index 86b972225ce76a..e36e4ef1abcdf7 100644 --- a/ArduPlane/ekf_check.cpp +++ b/ArduPlane/ekf_check.cpp @@ -112,7 +112,7 @@ bool Plane::ekf_over_threshold() return false; } - // Get EKF innovations normalised wrt the innovaton test limits. + // Get EKF innovations normalised wrt the innovation test limits. // A value above 1.0 means the EKF has rejected that sensor data float position_variance, vel_variance, height_variance, tas_variance; Vector3f mag_variance; @@ -157,7 +157,7 @@ void Plane::failsafe_ekf_event() ekf_check_state.failsafe_on = true; AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); - // if not in a VTOL mode requring position, then nothing needs to be done + // if not in a VTOL mode requiring position, then nothing needs to be done #if HAL_QUADPLANE_ENABLED if (!quadplane.in_vtol_posvel_mode()) { return; diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 122b3dc361d211..f49814aca9b903 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -140,7 +140,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { #if PARACHUTE == ENABLED parachute_release(); - //stop motors to avoide parachute tangling + //stop motors to avoid parachute tangling plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { @@ -183,7 +183,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { #if PARACHUTE == ENABLED parachute_release(); - //stop motors to avoide parachute tangling + //stop motors to avoid parachute tangling plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 3b2c27396f59d0..ffe578736aff14 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -261,7 +261,7 @@ void Plane::crash_detection_update(void) if (g.takeoff_throttle_min_accel > 0 && !throttle_suppressed) { // if you have an acceleration holding back throttle, but you met the - // accel threshold but still not fying, then you either shook/hit the + // accel threshold but still not flying, then you either shook/hit the // plane or it was a failed launch. crashed = true; crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS; diff --git a/ArduPlane/mode_acro.cpp b/ArduPlane/mode_acro.cpp index acf0f497523d80..c15970b9bdecec 100644 --- a/ArduPlane/mode_acro.cpp +++ b/ArduPlane/mode_acro.cpp @@ -68,7 +68,7 @@ void ModeAcro::stabilize() int32_t roll_error_cd = -ToDeg(acro_state.locked_roll_err)*100; plane.nav_roll_cd = ahrs.roll_sensor + roll_error_cd; // try to reduce the integrated angular error to zero. We set - // 'stabilze' to true, which disables the roll integrator + // 'stabilize' to true, which disables the roll integrator SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_servo_out(roll_error_cd, speed_scaler, true, false)); diff --git a/ArduPlane/mode_qacro.cpp b/ArduPlane/mode_qacro.cpp index b74a4343841611..d49e1e0fb6152f 100644 --- a/ArduPlane/mode_qacro.cpp +++ b/ArduPlane/mode_qacro.cpp @@ -9,7 +9,7 @@ bool ModeQAcro::_enter() quadplane.transition->force_transition_complete(); attitude_control->relax_attitude_controllers(); - // disable yaw rate time contant to mantain old behaviour + // disable yaw rate time constant to maintain old behaviour quadplane.disable_yaw_rate_time_constant(); IGNORE_RETURN(ahrs.get_quaternion(plane.mode_acro.acro_state.q)); diff --git a/ArduPlane/mode_qrtl.cpp b/ArduPlane/mode_qrtl.cpp index e31e4681ada0cf..9be1c962bd6a4b 100644 --- a/ArduPlane/mode_qrtl.cpp +++ b/ArduPlane/mode_qrtl.cpp @@ -126,7 +126,7 @@ void ModeQRTL::run() ftype alt_diff; if (!stopping_loc.get_alt_distance(plane.next_WP_loc, alt_diff) || is_positive(alt_diff)) { - // climb finshed or cant get alt diff, head home + // climb finished or cant get alt diff, head home submode = SubMode::RTL; plane.prev_WP_loc = plane.current_loc; diff --git a/ArduPlane/mode_qstabilize.cpp b/ArduPlane/mode_qstabilize.cpp index 659d674736f452..2f78a210fb3c2d 100644 --- a/ArduPlane/mode_qstabilize.cpp +++ b/ArduPlane/mode_qstabilize.cpp @@ -83,7 +83,7 @@ void ModeQStabilize::set_tailsitter_roll_pitch(const float roll_input, const flo plane.quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd); } -// set the desired roll and pitch for normal quadplanes, also limited by forward flight limtis +// set the desired roll and pitch for normal quadplanes, also limited by forward flight limits void ModeQStabilize::set_limited_roll_pitch(const float roll_input, const float pitch_input) { plane.nav_roll_cd = roll_input * MIN(plane.roll_limit_cd, plane.quadplane.aparm.angle_max); diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index 67dee708b50b7b..38229d2f351344 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -67,7 +67,7 @@ void QuadPlane::motor_test_output() // sanity check throttle values if (pwm >= RC_Channel::RC_MIN_LIMIT_PWM && pwm <= RC_Channel::RC_MAX_LIMIT_PWM) { - // turn on motor to specified pwm vlaue + // turn on motor to specified pwm value motors->output_test_seq(motor_test.seq, pwm); } else { motor_test_stop(); diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index b60b442646e69d..76846b0fe6ed64 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -73,7 +73,7 @@ void Plane::loiter_angle_update(void) loiter.next_sum_lap_cd = loiter.sum_cd + lap_check_interval_cd; } else if (!loiter.reached_target_alt && labs(loiter.sum_cd) >= loiter.next_sum_lap_cd) { - // check every few laps for scenario where up/downdrafts inhibit you from loitering up/down for too long + // check every few laps for scenario where up/downward inhibit you from loitering up/down for too long loiter.unable_to_acheive_target_alt = labs(current_loc.alt - loiter.start_lap_alt_cm) < 500; loiter.start_lap_alt_cm = current_loc.alt; loiter.next_sum_lap_cd += lap_check_interval_cd; @@ -188,7 +188,7 @@ void Plane::calc_airspeed_errors() get_throttle_input()) + ((int32_t)aparm.airspeed_min * 100); } #if OFFBOARD_GUIDED == ENABLED - } else if (control_mode == &mode_guided && guided_state.target_airspeed_cm > 0.0) { // if offbd guided speed change cmd not set, then this section is skipped + } else if (control_mode == &mode_guided && guided_state.target_airspeed_cm > 0.0) { // if offboard guided speed change cmd not set, then this section is skipped // offboard airspeed demanded uint32_t now = AP_HAL::millis(); float delta = 1e-3f * (now - guided_state.target_airspeed_time_ms); diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 93d062d38d2cf7..9557637af40d58 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -400,7 +400,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Param: ASSIST_ALT // @DisplayName: Quadplane assistance altitude - // @Description: This is the altitude below which quadplane assistance will be triggered. This acts the same way as Q_ASSIST_ANGLE and Q_ASSIST_SPEED, but triggers if the aircraft drops below the given altitude while the VTOL motors are not running. A value of zero disables this feature. The altutude is calculated as being above ground level. The height above ground is given from a Lidar used if available and RNGFND_LANDING=1. Otherwise it comes from terrain data if TERRAIN_FOLLOW=1 and comes from height above home otherwise. + // @Description: This is the altitude below which quadplane assistance will be triggered. This acts the same way as Q_ASSIST_ANGLE and Q_ASSIST_SPEED, but triggers if the aircraft drops below the given altitude while the VTOL motors are not running. A value of zero disables this feature. The altitude is calculated as being above ground level. The height above ground is given from a Lidar used if available and RNGFND_LANDING=1. Otherwise it comes from terrain data if TERRAIN_FOLLOW=1 and comes from height above home otherwise. // @Units: m // @Range: 0 120 // @Increment: 1 @@ -524,7 +524,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Param: FWD_THR_USE // @DisplayName: Q mode forward throttle use - // @Description: This parameter determines when the feature that uses forward throttle insread of forward tilt is used. The amount of forward throttle is controlled by the Q_FWD_THR_GAIN parameter. The maximum amount of forward pitch allowed is controlled by the Q_FWD_PIT_LIM parameter. Q_FWD_THR_USE = 0 disables the feature. Q_FWD_THR_USE = 1 enables the feature in all position controlled modes such as QLOITER, QLAND, QRTL and VTOL TAKEOFF. Q_FWD_THR_USE = 2 enables the feature in all Q modes except QAUTOTUNE and QACRO. When enabling the feature, the legacy method of controlling forward throttle use via velocity controller error should be disabled by setting Q_VFWD_GAIN to 0. Do not use this feature with tailsitters. + // @Description: This parameter determines when the feature that uses forward throttle instead of forward tilt is used. The amount of forward throttle is controlled by the Q_FWD_THR_GAIN parameter. The maximum amount of forward pitch allowed is controlled by the Q_FWD_PIT_LIM parameter. Q_FWD_THR_USE = 0 disables the feature. Q_FWD_THR_USE = 1 enables the feature in all position controlled modes such as QLOITER, QLAND, QRTL and VTOL TAKEOFF. Q_FWD_THR_USE = 2 enables the feature in all Q modes except QAUTOTUNE and QACRO. When enabling the feature, the legacy method of controlling forward throttle use via velocity controller error should be disabled by setting Q_VFWD_GAIN to 0. Do not use this feature with tailsitters. // @Values: 0:Off,1:On in all position controlled Q modes,2:On in all Q modes except QAUTOTUNE and QACRO // @User: Standard AP_GROUPINFO("FWD_THR_USE", 37, QuadPlane, q_fwd_thr_use, uint8_t(FwdThrUse::OFF)), diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index ae6f3c69c5fc17..ced42525788e83 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -924,7 +924,7 @@ void Plane::indicate_waiting_for_rud_neutral_to_takeoff(void) SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, 0); channel_function_mixer(SRV_Channel::k_rudder, SRV_Channel::k_elevator, SRV_Channel::k_vtail_right, SRV_Channel::k_vtail_left); if (!SRV_Channels::function_assigned(SRV_Channel::k_rudder) && !SRV_Channels::function_assigned(SRV_Channel::k_vtail_left)) { - // if no rudder indication possible, neutral elevons during wait becuase on takeoff stance they are usually both full up + // if no rudder indication possible, neutral elevons during wait because on takeoff stance they are usually both full up SRV_Channels::set_output_scaled(SRV_Channel::k_elevon_right, 0); SRV_Channels::set_output_scaled(SRV_Channel::k_elevon_left, 0); } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 6f21b75abc7519..7c7066bef06b60 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -257,7 +257,7 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) if (control_mode == &new_mode) { // don't switch modes if we are already in the correct mode. - // only make happy noise if using a difent method to switch, this stops beeping for repeated change mode requests from GCS + // only make happy noise if using a different method to switch, this stops beeping for repeated change mode requests from GCS if ((reason != control_mode_reason) && (reason != ModeReason::INITIALISED)) { AP_Notify::events.user_mode_change = 1; } diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index ffc8c76c252636..f40fa33d1f26eb 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -27,7 +27,7 @@ const AP_Param::GroupInfo Tailsitter::var_info[] = { // @Param: ENABLE // @DisplayName: Enable Tailsitter // @Values: 0:Disable, 1:Enable, 2:Enable Always - // @Description: This enables Tailsitter functionality. A value of 2 forces Qassist active and always stabilize in forward flight with airmode for stabalisation at 0 throttle, for use on vehicles with no control surfaces, vehicle will not arm in forward flight modes, see also Q_OPTIONS "Mtrs_Only_Qassist" + // @Description: This enables Tailsitter functionality. A value of 2 forces Qassist active and always stabilize in forward flight with airmode for stabilisation at 0 throttle, for use on vehicles with no control surfaces, vehicle will not arm in forward flight modes, see also Q_OPTIONS "Mtrs_Only_Qassist" // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("ENABLE", 1, Tailsitter, enable, 0, AP_PARAM_FLAG_ENABLE), @@ -161,7 +161,7 @@ const AP_Param::GroupInfo Tailsitter::var_info[] = { // @Param: MIN_VO // @DisplayName: Tailsitter Disk loading minimum outflow speed - // @Description: Use in conjunction with disk therory gain scaling and Q_TAILSIT_DSKLD to specify minumum airspeed over control surfaces, this will be used to boost throttle, when decending for example, 0 disables + // @Description: Use in conjunction with disk theory gain scaling and Q_TAILSIT_DSKLD to specify minumum airspeed over control surfaces, this will be used to boost throttle, when descending for example, 0 disables // @Range: 0 15 AP_GROUPINFO("MIN_VO", 22, Tailsitter, disk_loading_min_outflow, 0), @@ -330,7 +330,7 @@ void Tailsitter::output(void) SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, throttle_pwm); SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, throttle_pwm); - // throttle output is not used by AP_Motors so might have diffrent PWM range, set scaled + // throttle output is not used by AP_Motors so might have different PWM range, set scaled SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle * 100.0); } } @@ -513,7 +513,7 @@ void Tailsitter::output(void) bool Tailsitter::transition_fw_complete(void) { if (!plane.arming.is_armed_and_safety_off()) { - // instant trainsition when disarmed, no message + // instant transition when disarmed, no message return true; } if (labs(quadplane.ahrs_view->pitch_sensor) > transition_angle_fw*100) { @@ -539,7 +539,7 @@ bool Tailsitter::transition_fw_complete(void) bool Tailsitter::transition_vtol_complete(void) const { if (!plane.arming.is_armed_and_safety_off()) { - // instant trainsition when disarmed, no message + // instant transition when disarmed, no message return true; } // for vectored tailsitters at zero pilot throttle @@ -634,7 +634,7 @@ void Tailsitter::speed_scaling(void) float spd_scaler = 1.0f; float disk_loading_min_throttle = 0.0; - // Scaleing with throttle + // Scaling with throttle float throttle_scaler = throttle_scale_max; if (is_positive(throttle)) { throttle_scaler = constrain_float(hover_throttle / throttle, gain_scaling_min, throttle_scale_max); @@ -930,7 +930,7 @@ bool Tailsitter_Transition::allow_stick_mixing() const if (tailsitter.in_vtol_transition()) { return false; } - // Transitioning into fixed wing flight, leveling off + // Transitioning into fixed wing flight, levelling off if ((transition_state == TRANSITION_DONE) && (fw_limit_start_ms != 0)) { return false; } diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 73290a5f060c0e..5574ad2c9b0c10 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -238,7 +238,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void) return auto_state.takeoff_pitch_cd * scalar; } - // are we entering the region where we want to start leveling off before we reach takeoff alt? + // are we entering the region where we want to start levelling off before we reach takeoff alt? if (auto_state.sink_rate < -0.1f) { float sec_to_target = (remaining_height_to_target_cm * 0.01f) / (-auto_state.sink_rate); if (sec_to_target > 0 && diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 8f5c37f5d599fa..e8babe5e86d93b 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -39,7 +39,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = { // @Param: TYPE // @DisplayName: Tiltrotor type - // @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE. A vectored yaw tiltrotor will use the tilt of the motors to control yaw in hover, Bicopter tiltrottor must use the tailsitter frame class (10) + // @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE. A vectored yaw tiltrotor will use the tilt of the motors to control yaw in hover, Bicopter tiltrotor must use the tailsitter frame class (10) // @Values: 0:Continuous,1:Binary,2:VectoredYaw,3:Bicopter AP_GROUPINFO("TYPE", 5, Tiltrotor, type, TILT_TYPE_CONTINUOUS), @@ -115,7 +115,7 @@ void Tiltrotor::setup() && (type != TILT_TYPE_BICOPTER)); - // check if there are any perminant VTOL motors + // check if there are any permanent VTOL motors for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; ++i) { if (motors->is_motor_enabled(i) && ((tilt_mask & (1U<<1)) == 0)) { // enabled motor not set in tilt mask @@ -193,7 +193,7 @@ void Tiltrotor::slew(float newtilt) SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, 1000 * current_tilt); } -// return the current tilt value that represens forward flight +// return the current tilt value that represents forward flight // tilt wings can sustain forward flight with some amount of wing tilt float Tiltrotor::get_fully_forward_tilt() const { diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 12e300732e66f7..f170667859e8f5 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -49,7 +49,7 @@ class Parameters { // Layout version number, always key zero. // k_param_format_version = 0, - k_param_software_type, // unusued + k_param_software_type, // unused k_param_g2, // 2nd block of parameters diff --git a/ArduSub/ReleaseNotes.txt b/ArduSub/ReleaseNotes.txt index 937999ce180a49..6d68f5216e7f51 100644 --- a/ArduSub/ReleaseNotes.txt +++ b/ArduSub/ReleaseNotes.txt @@ -704,7 +704,7 @@ Changes from 3.1.4 11) CLI removed from APM1/2 to save flash space, critical functions moved to MAVLink: a) Individual motor tests (see MP's Initial Setup > Optional Hardware > Motor Test) b) compassmot (see MP's Initial Setup > Optional Hardware > Compass/Motor Calib) - c) parameter reset to factory defautls (see MP's Config/Tuning > Full Parameter List > Reset to Default) + c) parameter reset to factory defaults (see MP's Config/Tuning > Full Parameter List > Reset to Default) ------------------------------------------------------------------ ArduCopter 3.1.5 27-May-2014 / 3.1.5-rc2 20-May-2014 Changes from 3.1.5-rc1 diff --git a/ArduSub/defines.h b/ArduSub/defines.h index 170b466966cbdf..87e45820bc9828 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -39,7 +39,7 @@ enum autopilot_yaw_mode { #define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received) #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last -#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicotpers) +#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters) #define WP_YAW_BEHAVIOR_CORRECT_XTRACK 4 // point towards intermediate position target during line following diff --git a/ArduSub/mode_poshold.cpp b/ArduSub/mode_poshold.cpp index 8c1b389464c1ab..b85e359ede568c 100644 --- a/ArduSub/mode_poshold.cpp +++ b/ArduSub/mode_poshold.cpp @@ -93,7 +93,7 @@ void ModePoshold::run() } else { // hold current heading - // this check is required to prevent bounce back after very fast yaw maneuvers + // this check is required to prevent bounce back after very fast yaw manoeuvres // the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped if (tnow < sub.last_pilot_yaw_input_ms + 250) { // give 250ms to slow down, then set target heading target_yaw_rate = 0; // Stop rotation on yaw axis diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 8923e6bd1ceb38..32ac39b5bddf4f 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -175,7 +175,7 @@ class Blimp : public AP_Vehicle RCMapper rcmap; - // intertial nav alt when we armed + // inertial nav alt when we armed float arming_altitude_m; // Failsafe diff --git a/Blimp/Fins.h b/Blimp/Fins.h index 6e225580385e32..89541eea7cd97d 100644 --- a/Blimp/Fins.h +++ b/Blimp/Fins.h @@ -50,7 +50,7 @@ class Fins uint16_t _speed_hz; // speed in hz to send updates to motors float _throttle_avg_max; // last throttle input from set_throttle_avg_max - float _time; //current timestep + float _time; // current timestamp bool _armed; // 0 if disarmed, 1 if armed diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index b309bbfe1668d3..8d6060d06b5a65 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 ade5317e2a9787..c1fe903b698414 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 f089f01d4669da..8023985eabb969 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h @@ -20,10 +20,10 @@ class AC_AttitudeControl_Multi_6DoF : public AC_AttitudeControl_Multi { // 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 0efe05f36cab94..caf06d826ebcea 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 fd6ad741b3e499..087f4b2274c51d 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 c4585b21c1c652..38d7ecb039dca7 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; diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 206050f7022131..e152af499993f8 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -158,7 +158,7 @@ class AC_AutoTune AP_AHRS_View *ahrs_view, AP_InertialNav *inertial_nav); - // send intermittant updates to user on status of tune + // send intermittent updates to user on status of tune virtual void do_gcs_announcements() = 0; // send post test updates to user diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index 346a8143fe5115..d72a6db6fe4c09 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -678,7 +678,7 @@ void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const } } -// report gain formating helper +// report gain formatting helper void AC_AutoTune_Heli::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const { gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string); @@ -1353,7 +1353,7 @@ void AC_AutoTune_Heli::set_gains_post_tune(AxisType test_axis) } // updating_rate_ff_up - adjust FF to ensure the target is reached -// FF is adjusted until rate requested is acheived +// FF is adjusted until rate requested is achieved void AC_AutoTune_Heli::updating_rate_ff_up(float &tune_ff, float rate_target, float meas_rate, float meas_command) { @@ -1565,7 +1565,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga // once finished with sweep of frequencies, cnt = 12 is used to then tune for max response gain if (freq_cnt >= 12 && is_equal(start_freq,stop_freq)) { if (gain[freq_cnt] < max_resp_gain && tune_p < AUTOTUNE_SP_MAX && !find_peak) { - // keep increasing tuning gain unless phase changes or max response gain is acheived + // keep increasing tuning gain unless phase changes or max response gain is achieved if (phase[freq_cnt]-phase_max > 20.0f && phase[freq_cnt] < 210.0f) { freq[freq_cnt] += 0.5 * test_freq_incr; find_peak = true; @@ -1837,7 +1837,7 @@ void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq, float gain, float pha phase); } -// reset the test vaariables for each vehicle +// reset the test variables for each vehicle void AC_AutoTune_Heli::reset_vehicle_test_variables() { // reset dwell test variables if sweep was interrupted in order to restart sweep diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index cf941737919c97..6329563b02bae7 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -60,7 +60,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // load test gains void load_test_gains() override; - // reset the test vaariables for heli + // reset the test variables for heli void reset_vehicle_test_variables() override; // reset the update gain variables for heli @@ -111,7 +111,7 @@ class AC_AutoTune_Heli : public AC_AutoTune void Log_AutoTuneSweep() override; void Log_Write_AutoTuneSweep(float freq, float gain, float phase); - // send intermittant updates to user on status of tune + // send intermittent updates to user on status of tune void do_gcs_announcements() override; // send post test updates to user @@ -161,7 +161,7 @@ class AC_AutoTune_Heli : public AC_AutoTune void dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase, DwellType dwell_type); // updating_rate_ff_up - adjust FF to ensure the target is reached - // FF is adjusted until rate requested is acheived + // FF is adjusted until rate requested is achieved void updating_rate_ff_up(float &tune_ff, float rate_target, float meas_rate, float meas_command); // updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not exceed exceed max response gain @@ -185,7 +185,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // exceeded_freq_range - ensures tuning remains inside frequency range bool exceeded_freq_range(float frequency); - // report gain formating helper + // report gain formatting helper void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const; // updating rate FF variables diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index 6e414b76d8b914..bf988c187ae9f2 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -484,7 +484,7 @@ void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const } } -// report gain formating helper +// report gain formatting helper void AC_AutoTune_Multi::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const { gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string); diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.h b/libraries/AC_AutoTune/AC_AutoTune_Multi.h index 5374a432f849a0..b2a02fcdc6bce8 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.h @@ -53,7 +53,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // load test gains void load_test_gains() override; - // reset the test vaariables for multi + // reset the test variables for multi void reset_vehicle_test_variables() override {}; // reset the update gain variables for multi @@ -62,7 +62,7 @@ class AC_AutoTune_Multi : public AC_AutoTune void test_init() override; void test_run(AxisType test_axis, const float dir_sign) override; - // send intermittant updates to user on status of tune + // send intermittent updates to user on status of tune void do_gcs_announcements() override; // send post test updates to user @@ -160,7 +160,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // P is increased until we achieve our target within a reasonable time void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max); - // report gain formating helper + // report gain formatting helper void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const; // parameters diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 69f9a6dcbb5cb7..7ce790517d942b 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -101,7 +101,7 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = { // @Param: FW_V_P // @DisplayName: Velocity (horizontal) P gain - // @Description: Velocity (horizontal) P gain. Determines the propotion of the target acceleration based on the velocity error. + // @Description: Velocity (horizontal) P gain. Determines the proportion of the target acceleration based on the velocity error. // @Range: 0.1 6.0 // @Increment: 0.1 // @User: Advanced @@ -153,7 +153,7 @@ bool AC_Autorotation::update_hs_glide_controller(float dt) _flags.bad_rpm = false; _flags.bad_rpm_warning = false; - // Get current rpm and update healthly signal counters + // Get current rpm and update healthy signal counters _current_rpm = get_rpm(true); if (_unhealthy_rpm_counter <=30) { @@ -220,7 +220,7 @@ float AC_Autorotation::get_rpm(bool update_counter) //Get RPM value uint8_t instance = _param_rpm_instance; - //Check RPM sesnor is returning a healthy status + //Check RPM sensor is returning a healthy status if (!rpm->get_rpm(instance, current_rpm) || current_rpm <= -1) { //unhealthy, rpm unreliable _flags.bad_rpm = true; @@ -322,7 +322,7 @@ void AC_Autorotation::update_forward_speed_controller(void) _delta_speed_fwd = _speed_forward - _speed_forward_last; //(cm/s) _speed_forward_last = _speed_forward; //(cm/s) - // Limitng the target velocity based on the max acceleration limit + // Limiting the target velocity based on the max acceleration limit if (_cmd_vel < _vel_target) { _cmd_vel += _accel_max * _dt; if (_cmd_vel > _vel_target) { diff --git a/libraries/AC_Autorotation/AC_Autorotation.h b/libraries/AC_Autorotation/AC_Autorotation.h index d89fe88dc42379..d5cfa52097b3f1 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.h +++ b/libraries/AC_Autorotation/AC_Autorotation.h @@ -32,7 +32,7 @@ class AC_Autorotation float get_last_collective() const { return _collective_out; } bool is_enable(void) { return _param_enable; } void Log_Write_Autorotation(void) const; - void update_forward_speed_controller(void); // Update foward speed controller + void update_forward_speed_controller(void); // Update forward speed controller void set_desired_fwd_speed(void) { _vel_target = _param_target_speed; } // Overloaded: Set desired speed for forward controller to parameter value void set_desired_fwd_speed(float speed) { _vel_target = speed; } // Overloaded: Set desired speed to argument value int32_t get_pitch(void) const { return _pitch_target; } // Get pitch target diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 7b2e5fdf20f490..8e5067f3be6935 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -143,7 +143,7 @@ void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desir adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt); find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel); - // backup_vel_fence is set to zero after each fence incase the velocity is unset from previous methods + // backup_vel_fence is set to zero after each fence in case the velocity is unset from previous methods backup_vel_fence.zero(); adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt); find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel); @@ -229,7 +229,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa } // let user take control if they are backing away at a greater speed than what we have calculated - // this has to be done for x,y,z seperately. For eg, user is doing fine in "x" direction but might need backing up in "y". + // this has to be done for x,y,z separately. For eg, user is doing fine in "x" direction but might need backing up in "y". if (!is_zero(desired_backup_vel.x)) { if (is_positive(desired_backup_vel.x)) { desired_vel_cms.x = MAX(desired_vel_cms.x, desired_backup_vel.x); @@ -505,7 +505,7 @@ void AC_Avoid::limit_velocity_3D(float kP, float accel_cmss, Vector3f &desired_v return; } // create a margin_cm length vector in the direction of desired_vel_cms - // this will create larger margin towards the direction vehicle is traveling in + // this will create larger margin towards the direction vehicle is travelling in const Vector3f margin_vector = desired_vel_cms.normalized() * margin_cm; const Vector2f limit_direction_xy{obstacle_vector.x, obstacle_vector.y}; diff --git a/libraries/AC_Avoidance/AC_Avoid.h b/libraries/AC_Avoidance/AC_Avoid.h index 2f9f048dae2a80..6bccfb846d58b9 100644 --- a/libraries/AC_Avoidance/AC_Avoid.h +++ b/libraries/AC_Avoidance/AC_Avoid.h @@ -18,7 +18,7 @@ #define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter) #define AC_AVOID_ANGLE_MAX_PERCENT 0.75f // object avoidance max lean angle as a percentage (expressed in 0 ~ 1 range) of total vehicle max lean angle -#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happend in the last x ms +#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happened in the last x ms #define AC_AVOID_ACCEL_TIMEOUT_MS 200 // stored velocity used to calculate acceleration will be reset if avoidance is active after this many ms /* @@ -213,7 +213,7 @@ class AC_Avoid { AP_Int8 _behavior; // avoidance behaviour (slide or stop) AP_Float _backup_speed_max; // Maximum speed that will be used to back away (in m/s) AP_Float _alt_min; // alt below which Proximity based avoidance is turned off - AP_Float _accel_max; // maximum accelration while simple avoidance is active + AP_Float _accel_max; // maximum acceleration while simple avoidance is active AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable) diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.h b/libraries/AC_Avoidance/AP_OABendyRuler.h index b90b7d6cbb8e46..e282e647221942 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.h +++ b/libraries/AC_Avoidance/AP_OABendyRuler.h @@ -74,7 +74,7 @@ class AP_OABendyRuler { // BendyRuler parameters AP_Float _lookahead; // object avoidance will look this many meters ahead of vehicle AP_Float _bendy_ratio; // object avoidance will avoid major directional change if change in margin ratio is less than this param - AP_Int16 _bendy_angle; // object avoidance will try avoding change in direction over this much angle + AP_Int16 _bendy_angle; // object avoidance will try avoiding change in direction over this much angle AP_Int8 _bendy_type; // Type of BendyRuler to run // internal variables used by background thread diff --git a/libraries/AC_Avoidance/AP_OADatabase.cpp b/libraries/AC_Avoidance/AP_OADatabase.cpp index cc8dacab1b98df..aeae78098b9abc 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.cpp +++ b/libraries/AC_Avoidance/AP_OADatabase.cpp @@ -230,7 +230,7 @@ uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importanc return 0x0; } -// returns true when there's more work inthe queue to do +// returns true when there's more work in the queue to do bool AP_OADatabase::process_queue() { if (!healthy()) { diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index a15604c43b5384..749cb140ee24a1 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -925,7 +925,7 @@ bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &d } } } - // report error incase path not found + // report error in case path not found if (!success) { err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH; } diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index f95405ad711ede..48e91f6cc1269c 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -197,6 +197,6 @@ class AP_OADijkstra { uint8_t _log_num_points; uint8_t _log_visgraph_version; - // refernce to AP_OAPathPlanner options param + // reference to AP_OAPathPlanner options param AP_Int16 &_options; }; diff --git a/libraries/AC_CustomControl/AC_CustomControl.h b/libraries/AC_CustomControl/AC_CustomControl.h index c11a51fb00833a..bf0628302b72ad 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.h +++ b/libraries/AC_CustomControl/AC_CustomControl.h @@ -32,7 +32,7 @@ class AC_CustomControl { bool is_safe_to_run(void); void log_switch(void); - // zero index controller type param, only use it to acces _backend or _backend_var_info array + // zero index controller type param, only use it to access _backend or _backend_var_info array uint8_t get_type() { return _controller_type > 0 ? (_controller_type - 1) : 0; }; // User settable parameters diff --git a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp index d11caabc7eca56..222510c4f471d9 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp @@ -8,19 +8,19 @@ const AP_Param::GroupInfo AC_CustomControl_Empty::var_info[] = { // @Param: PARAM1 // @DisplayName: Empty param1 - // @Description: Dumy parameter for empty custom controller backend + // @Description: Dummy parameter for empty custom controller backend // @User: Advanced AP_GROUPINFO("PARAM1", 1, AC_CustomControl_Empty, param1, 0.0f), // @Param: PARAM2 // @DisplayName: Empty param2 - // @Description: Dumy parameter for empty custom controller backend + // @Description: Dummy parameter for empty custom controller backend // @User: Advanced AP_GROUPINFO("PARAM2", 2, AC_CustomControl_Empty, param2, 0.0f), // @Param: PARAM3 // @DisplayName: Empty param3 - // @Description: Dumy parameter for empty custom controller backend + // @Description: Dummy parameter for empty custom controller backend // @User: Advanced AP_GROUPINFO("PARAM3", 3, AC_CustomControl_Empty, param3, 0.0f), @@ -54,7 +54,7 @@ Vector3f AC_CustomControl_Empty::update(void) break; } - // arducopter main attitude controller already runned + // arducopter main attitude controller already ran // we don't need to do anything else gcs().send_text(MAV_SEVERITY_INFO, "empty custom controller working"); diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index e0196fadc67820..58ecaba08e031b 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -494,7 +494,7 @@ bool AC_Fence::check_fence_polygon() /// check_fence_circle - returns true if the circle fence (defined via /// parameters) has been freshly breached. May also set up a backup /// fence outside the fence and return a fresh breach if that backup -/// fence is breaced. +/// fence is braced. bool AC_Fence::check_fence_circle() { if (!(_enabled_fences & AC_FENCE_TYPE_CIRCLE)) { diff --git a/libraries/AC_Fence/AC_PolyFence_loader.h b/libraries/AC_Fence/AC_PolyFence_loader.h index 92d8bca51278b0..5c87b5b4a78ef5 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.h +++ b/libraries/AC_Fence/AC_PolyFence_loader.h @@ -6,7 +6,7 @@ // CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in // metres. This was a bug, and CIRCLE_INCLUSION was created to store // as a 32-bit float instead. We save as _INT in the case that the -// radius looks like an integer as a backwards-compatability measure. +// radius looks like an integer as a backwards-compatibility measure. // For 4.2 we might consider only loading _INT and always saving as // float, and in 4.3 considering _INT invalid enum class AC_PolyFenceType { @@ -352,7 +352,7 @@ class AC_PolyFence_loader #if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT /* - * FENCE_POINT protocol compatability + * FENCE_POINT protocol compatibility */ void handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg); void handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg); @@ -380,7 +380,7 @@ class AC_PolyFence_loader bool write_eos_to_storage(uint16_t &offset); // _total - reference to FENCE_TOTAL parameter. This is used - // solely for compatability with the FENCE_POINT protocol + // solely for compatibility with the FENCE_POINT protocol AP_Int8 &_total; const AP_Int16 &_options; uint8_t _old_total; diff --git a/libraries/AC_PID/AC_PI_2D.h b/libraries/AC_PID/AC_PI_2D.h index 2020134babafa8..c031104531b5f5 100644 --- a/libraries/AC_PID/AC_PI_2D.h +++ b/libraries/AC_PID/AC_PI_2D.h @@ -87,7 +87,7 @@ class AC_PI_2D { } _flags; // internal variables - float _dt; // timestep in seconds + float _dt; // time step in seconds Vector2f _integrator; // integrator value Vector2f _input; // last input for derivative float _filt_alpha; // input filter alpha diff --git a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp index bc641acd80c53b..7b7b088e48d24d 100644 --- a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp +++ b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp @@ -8,7 +8,7 @@ #include #include -// we need a boardconfig created so that the io processor is available +// we need a board config created so that the io processor is available #if HAL_WITH_IO_MCU #include #include diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 7019898b144e9a..57223e1f666c93 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -150,7 +150,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = { // @Param: TIMEOUT // @DisplayName: PrecLand retry timeout - // @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attemp a landing retry depending on PLND_STRICT parameter. + // @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT parameter. // @Range: 0 20 // @Units: s AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_sec, 4), @@ -400,7 +400,7 @@ bool AC_PrecLand::target_acquired() { if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) { if (_target_acquired) { - // just lost the landing target, inform the user. This message will only be sent once everytime target is lost + // just lost the landing target, inform the user. This message will only be sent once every time target is lost gcs().send_text(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost"); } // not had a sensor update since a long time @@ -622,7 +622,7 @@ bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body) } - // rotate vector based on sensor oriention to get correct body frame vector + // rotate vector based on sensor orientation to get correct body frame vector if (_orient != ROTATION_PITCH_270) { // by default, the vector is constructed downwards in body frame // hence, we do not do any rotation if the orientation is downwards diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index d7d866369d7770..a25b30c71f4f42 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -188,7 +188,7 @@ class AC_PrecLand AP_Float _xy_max_dist_desc; // Vehicle doing prec land will only descent vertically when horizontal error (in m) is below this limit AP_Int8 _strict; // PrecLand strictness AP_Int8 _retry_max; // PrecLand Maximum number of retires to a failed landing - AP_Float _retry_timeout_sec; // Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attemp a landing retry depending on PLND_STRICT param. + AP_Float _retry_timeout_sec; // Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT param. AP_Int8 _retry_behave; // Action to do when trying a landing retry AP_Float _sensor_min_alt; // PrecLand minimum height required for detecting target AP_Float _sensor_max_alt; // PrecLand maximum height the sensor can detect target diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp index c456288ca2d368..0d38584cee7770 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp @@ -7,11 +7,11 @@ #include #include -static const float MAX_POS_ERROR_M = 0.75f; // Maximum possition error for retry locations +static const float MAX_POS_ERROR_M = 0.75f; // Maximum position error for retry locations static const uint32_t FAILSAFE_INIT_TIMEOUT_MS = 7000; // Timeout in ms before failsafe measures are started. During this period vehicle is completely stopped to give user the time to take over static const float RETRY_OFFSET_ALT_M = 1.5f; // This gets added to the altitude of the retry location -// Initialize the state machine. This is called everytime vehicle switches mode +// Initialize the state machine. This is called every time vehicle switches mode void AC_PrecLand_StateMachine::init() { AC_PrecLand *_precland = AP::ac_precland(); @@ -24,14 +24,14 @@ void AC_PrecLand_StateMachine::init() // precland is not enabled, prec land state machine methods should not be called! return; } - // init is only called ONCE per mode change. So in a particuar mode we can retry only a finite times. + // init is only called ONCE per mode change. So in a particular mode we can retry only a finite times. // The counter will be reset if the statemachine is called from a different mode _retry_count = 0; // reset every other statemachine reset_failed_landing_statemachine(); } -// Reset the landing statemachines. This needs to be called everytime the landing target is back in sight. +// Reset the landing statemachines. This needs to be called every time the landing target is back in sight. // So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage void AC_PrecLand_StateMachine::reset_failed_landing_statemachine() { diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h index 8479be3c6abf7e..e52e3effc9b0da 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h @@ -23,7 +23,7 @@ class AC_PrecLand_StateMachine { // Do not allow copies CLASS_NO_COPY(AC_PrecLand_StateMachine); - // Initialize the state machine. This is called everytime vehicle switches mode + // Initialize the state machine. This is called every time vehicle switches mode void init(); // Current status of the precland state machine @@ -78,7 +78,7 @@ class AC_PrecLand_StateMachine { // Vector3f "retry_pos_m" is filled with the required location. Status retry_landing(Vector3f &retry_pos_m); - // Reset the landing statemachine. This needs to be called everytime the landing target is back in sight. + // Reset the landing statemachine. This needs to be called every time the landing target is back in sight. // So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage void reset_failed_landing_statemachine(); diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index 7eaa91a09bfea8..c6b026eb5628df 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -21,7 +21,7 @@ const AP_Param::GroupInfo AC_Sprayer::var_info[] = { // @Param: PUMP_RATE // @DisplayName: Pump speed - // @Description: Desired pump speed when traveling 1m/s expressed as a percentage + // @Description: Desired pump speed when travelling 1m/s expressed as a percentage // @Units: % // @Range: 0 100 // @User: Standard @@ -174,7 +174,7 @@ void AC_Sprayer::update() _speed_over_min_time = 0; } - // if testing pump output speed as if traveling at 1m/s + // if testing pump output speed as if travelling at 1m/s if (_flags.testing) { ground_speed = 100.0f; should_be_spraying = true; diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 752699a5291cc9..ca804a54916c94 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 498241e0252304..d76fcc90ce64e6 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -153,7 +153,7 @@ class AC_Circle 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 e63b9fc4450c99..913fbc237d2f4b 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 constant 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); diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index da7cfd5dd53472..9d82e541a4f928 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -103,7 +103,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = { // @Param: OFFSET_LAT // @DisplayName: GPS antenna lateral offset - // @Description: GPS antenna lateral offset. This describes the physical location offest from center of the GPS antenna on the aircraft. + // @Description: GPS antenna lateral offset. This describes the physical location offset from center of the GPS antenna on the aircraft. // @Values: 0:NoData,1:Left2m,2:Left4m,3:Left6m,4:Center,5:Right2m,6:Right4m,7:Right6m // @User: Advanced AP_GROUPINFO("OFFSET_LAT", 7, AP_ADSB, out_state.cfg.gpsOffsetLat, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M), diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index 80bb44d0333654..f9210a559a6b6d 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -155,7 +155,7 @@ class AP_ADSB { static uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber); // Trigger a Mode 3/A transponder IDENT. This should only be done when requested to do so by an Air Traffic Controller. - // See wikipedia for IDENT explaination https://en.wikipedia.org/wiki/Transponder_(aeronautics) + // See wikipedia for IDENT explanation https://en.wikipedia.org/wiki/Transponder_(aeronautics) bool ident_start() { if (!healthy() || ((out_state.cfg.rfSelect & UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED) == 0)) { return false; diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp index 473b34f3475c63..571f265905f7e4 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp @@ -140,7 +140,7 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co /* * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features * This function will override the MSB byte of the 24bit ICAO address. To ensure an invalid >24bit ICAO is never broadcasted, - * this function is used to create the encoded verison without ever writing to the actual ICAO number. It's created on-demand + * this function is used to create the encoded version without ever writing to the actual ICAO number. It's created on-demand */ uint32_t AP_ADSB_uAvionix_MAVLink::encode_icao(const uint32_t icao_id) const { diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 52a0c42e5a2bd3..e043f24df7d2af 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -242,7 +242,7 @@ void AP_AHRS::init() #endif #if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - // convert to new custom rotaton + // convert to new custom rotation // PARAMETER_CONVERSION - Added: Nov-2021 if (_board_orientation == ROTATION_CUSTOM_OLD) { _board_orientation.set_and_save(ROTATION_CUSTOM_1); @@ -590,7 +590,7 @@ void AP_AHRS::update_EKF2(void) float &abias = state.accel_bias.z; EKF2.getAccelZBias(abias); - // This EKF is currently using primary_imu, and abias applies to only that IMU + // This EKF is currently using primary_imu, and a bias applies to only that IMU Vector3f accel = _ins.get_accel(primary_accel); accel.z -= abias; state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; @@ -653,7 +653,7 @@ void AP_AHRS::update_EKF3(void) // use the same IMU as the primary EKF and correct for gyro drift state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift; - // get 3-axis accel bias festimates for active EKF (this is usually for the primary IMU) + // get 3-axis accel bias estimates for active EKF (this is usually for the primary IMU) Vector3f &abias = state.accel_bias; EKF3.getAccelBias(-1,abias); @@ -821,7 +821,7 @@ bool AP_AHRS::airspeed_sensor_enabled(void) const // special case for when backend is rejecting airspeed data in // an armed fly_forward state and not dead reckoning. Then the // airspeed data is highly suspect and will be rejected. We - // will use the synthentic airspeed instead + // will use the synthetic airspeed instead return false; } return true; @@ -1500,7 +1500,7 @@ bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const } // Get a derivative of the vertical position which is kinematically consistent with the vertical position is required by some control loops. -// This is different to the vertical velocity from the EKF which is not always consistent with the verical position due to the various errors that are being corrected for. +// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for. bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const { switch (active_EKF_type()) { @@ -2111,7 +2111,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f #if HAL_EXTERNAL_AHRS_ENABLED // Always check external AHRS if enabled - // it is a source for IMU data even if not being used as direct AHRS replacment + // it is a source for IMU data even if not being used as direct AHRS replacement if (AP::externalAHRS().enabled() || (ekf_type() == EKFType::EXTERNAL)) { if (!AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len)) { return false; @@ -2916,7 +2916,7 @@ void AP_AHRS::set_terrain_hgt_stable(bool stable) #endif } -// return the innovations for the primariy EKF +// return the innovations for the primarily EKF // boolean false is returned if innovations are not available bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const { @@ -2980,7 +2980,7 @@ bool AP_AHRS::is_vibration_affected() const // get_variances - provides the innovations normalised using the innovation variance where a value of 0 // indicates prefect consistency between the measurement and the EKF solution and a value of 1 is the maximum -// inconsistency that will be accpeted by the filter +// inconsistency that will be accepted by the filter // boolean false is returned if variances are not available bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 3252c4d7896b5c..df722c5cc52b07 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -271,7 +271,7 @@ AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result) // additional error buildup. // Note that we can get significant renormalisation values - // when we have a larger delta_t due to a glitch eleswhere in + // when we have a larger delta_t due to a glitch elsewhere in // APM, such as a I2c timeout or a set of EEPROM writes. While // we would like to avoid these if possible, if it does happen // we don't want to compound the error by making DCM less @@ -428,7 +428,7 @@ bool AP_AHRS_DCM::use_compass(void) return false; } if (!AP::ahrs().get_fly_forward() || !have_gps()) { - // we don't have any alterative to the compass + // we don't have any alternative to the compass return true; } if (AP::gps().ground_speed() < GPS_SPEED_MIN) { @@ -463,7 +463,7 @@ bool AP_AHRS_DCM::get_quaternion(Quaternion &quat) const } // yaw drift correction using the compass or GPS -// this function prodoces the _omega_yaw_P vector, and also +// this function produces the _omega_yaw_P vector, and also // contributes to the _omega_I.z long term yaw drift estimate void AP_AHRS_DCM::drift_correction_yaw(void) @@ -573,8 +573,8 @@ AP_AHRS_DCM::drift_correction_yaw(void) // that depends on the spin rate. See the fastRotations.pdf // paper from Bill Premerlani // We also adjust the gain depending on the rate of change of horizontal velocity which - // is proportional to how observable the heading is from the acceerations and GPS velocity - // The accelration derived heading will be more reliable in turns than compass or GPS + // is proportional to how observable the heading is from the accelerations and GPS velocity + // The acceleration derived heading will be more reliable in turns than compass or GPS _omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain(); if (use_fast_gains()) { @@ -1061,7 +1061,7 @@ bool AP_AHRS_DCM::airspeed_estimate(float &airspeed_ret) const bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret) const { // airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order: - // airspeed as filled-in by an enabled airsped sensor + // airspeed as filled-in by an enabled airspeed sensor // if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation // Or if none of the above, fills-in using the previous airspeed estimate // Return false: if we are using the previous airspeed estimate @@ -1085,7 +1085,7 @@ bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret) } // airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order: -// airspeed as filled-in by an enabled airsped sensor +// airspeed as filled-in by an enabled airspeed sensor // if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation // Or if none of the above, fills-in using the previous airspeed estimate // Return false: if we are using the previous airspeed estimate diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index c7baf1634397b9..690ef22810bed0 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -172,7 +172,7 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { void reset(bool recover_eulers); // airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order: - // airspeed as filled-in by an enabled airsped sensor + // airspeed as filled-in by an enabled airspeed sensor // if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation // Or if none of the above, fills-in using the previous airspeed estimate // Return false: if we are using the previous airspeed estimate diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index 897e3e6679e28c..c08a4dea0318f9 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -141,7 +141,7 @@ void AP_AIS::update() uint8_t msg_parts[_incoming.num - 1]; for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) { // look for the rest of the message from the start of the buffer - // we assume the mesage has be received in the correct order + // we assume the message has be received in the correct order if (_AIVDM_buffer[i].num == (index + 1) && _AIVDM_buffer[i].total == _incoming.total && _AIVDM_buffer[i].ID == _incoming.ID) { msg_parts[index] = i; index++; @@ -349,11 +349,11 @@ void AP_AIS::clear_list_item(uint16_t index) } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -// Functions for decoding AIVDM payload mesages +// Functions for decoding AIVDM payload messages bool AP_AIS::payload_decode(const char *payload) { - // the mesage type is defined by the first character + // the message type is defined by the first character const uint8_t type = payload_char_decode(payload[0]); switch (type) { @@ -674,7 +674,7 @@ uint32_t AP_AIS::get_bits(const char *payload, uint16_t low, uint16_t high) } // read the specified bits from the char array each char giving 6 bits -// As the values are a arbitrary length the sign bit is in the wrong place for standard length varables +// As the values are a arbitrary length the sign bit is in the wrong place for standard length variables int32_t AP_AIS::get_bits_signed(const char *payload, uint16_t low, uint16_t high) { uint32_t value = get_bits(payload, low, high); @@ -829,7 +829,7 @@ AP_AIS *AP_AIS::get_singleton() { #else // Dummy methods are required to allow functionality to be enabled for Rover. -// It is not posible to compile in or out the full code based on vehicle type due to limitations +// It is not possible to compile in or out the full code based on vehicle type due to limitations // of the handling of `APM_BUILD_TYPE` define. // These dummy methods minimise flash cost in that case. diff --git a/libraries/AP_AIS/AP_AIS.h b/libraries/AP_AIS/AP_AIS.h index 2707de2bf11fc7..d55a08c82f8beb 100644 --- a/libraries/AP_AIS/AP_AIS.h +++ b/libraries/AP_AIS/AP_AIS.h @@ -125,7 +125,7 @@ class AP_AIS // decode each term bool decode_latest_term() WARN_IF_UNUSED; - // varables for decoding NMEA sentence + // variables for decoding NMEA sentence char _term[AIVDM_PAYLOAD_SIZE]; // buffer for the current term within the current sentence uint8_t _term_offset; // offset within the _term buffer where the next character should be placed uint8_t _term_number; // term index within the current sentence diff --git a/libraries/AP_AccelCal/AccelCalibrator.cpp b/libraries/AP_AccelCal/AccelCalibrator.cpp index 5e90912bda77e6..2cca0cb009f794 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.cpp +++ b/libraries/AP_AccelCal/AccelCalibrator.cpp @@ -36,7 +36,7 @@ _sample_buffer(nullptr) /* Select options, initialise variables and initiate accel calibration Options: - Fit Type: Will assume that if accelerometer static samples around all possible orientatio + Fit Type: Will assume that if accelerometer static samples around all possible orientation are spread in space will cover a surface of AXIS_ALIGNED_ELLIPSOID or any general ELLIPSOID as chosen @@ -173,7 +173,7 @@ bool AccelCalibrator::get_sample(uint8_t i, Vector3f& s) const { return true; } -// returns truen and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure +// returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure // returns false if no correct parameter exists to be applied along with existing sample without corrections bool AccelCalibrator::get_sample_corrected(uint8_t i, Vector3f& s) const { if (_status != ACCEL_CAL_SUCCESS || !get_sample(i,s)) { @@ -199,7 +199,7 @@ void AccelCalibrator::check_for_timeout() { } } -// returns spherical fit paramteters +// returns spherical fit parameters void AccelCalibrator::get_calibration(Vector3f& offset) const { offset = -_param.s.offset; } @@ -288,7 +288,7 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { break; case ACCEL_CAL_COLLECTING_SAMPLE: - // Calibrator is waiting on collecting samples from acceleromter for amount of + // Calibrator is waiting on collecting samples from accelerometer for amount of // time as requested by user/GCS if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) { break; @@ -309,7 +309,7 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { case ACCEL_CAL_FAILED: // Calibration has failed with reasons that can range from - // bad sample data leading to faillure in tolerance test to lack of distinct samples + // bad sample data leading to failure in tolerance test to lack of distinct samples if (_status == ACCEL_CAL_NOT_STARTED) { break; } diff --git a/libraries/AP_AccelCal/AccelCalibrator.h b/libraries/AP_AccelCal/AccelCalibrator.h index df06da578dbfea..3e3a04ffb52bd0 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.h +++ b/libraries/AP_AccelCal/AccelCalibrator.h @@ -64,7 +64,7 @@ class AccelCalibrator { // to averaged acc over time bool get_sample(uint8_t i, Vector3f& s) const; - // returns truen and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure + // returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure // returns false if no correct parameter exists to be applied along with existing sample without corrections bool get_sample_corrected(uint8_t i, Vector3f& s) const; diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 341aa7aac94407..a13480b531c7e9 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -156,7 +156,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _OFF_PCNT // @DisplayName: Maximum offset cal speed error - // @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibraions before a warning is issued. This potential speed error is in percent of ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered. + // @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered. // @Range: 0.0 10.0 // @Units: % // @User: Advanced @@ -632,7 +632,7 @@ void AP_Airspeed::read(uint8_t i) if (!prev_healthy) { // if the previous state was not healthy then we should not // use an IIR filter, otherwise a bad reading will last for - // some time after the sensor becomees healthy again + // some time after the sensor becomes healthy again state[i].filtered_pressure = airspeed_pressure; } else { state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure; diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index 564d59981465e0..5574f807557a67 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -56,7 +56,7 @@ class Airspeed_Calibration { private: // state of kalman filter for airspeed ratio estimation - Matrix3f P; // covarience matrix + Matrix3f P; // covariance matrix const float Q0; // process noise matrix top left and middle element const float Q1; // process noise matrix bottom right element Vector3f state; // state vector diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 5836270bf49567..2deeb427c09c34 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -42,7 +42,7 @@ class AP_Airspeed_Backend { // return the current temperature in degrees C, if available virtual bool get_temperature(float &temperature) = 0; - // true if sensor reads airspeed directly, not via pressue + // true if sensor reads airspeed directly, not via pressure virtual bool has_airspeed() {return false;} // return airspeed in m/s if available diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp index 3da9c968e2f829..c0a8e6aedce1c3 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp @@ -96,7 +96,7 @@ bool AP_Airspeed_NMEA::get_airspeed(float &airspeed) } // return the current temperature in degrees C -// the main update is done in the get_pressue function +// the main update is done in the get_pressure function // this just reports the value bool AP_Airspeed_NMEA::get_temperature(float &temperature) { diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index e68fc3cd210f06..bf17969f37fea5 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -261,7 +261,7 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press) flow_SDP3X = 0.0f; } - // diffential pressure through pitot tube + // differential pressure through pitot tube float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f))); // uncorrected pressure diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index ad65f258f92867..898f566d0f2723 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -873,7 +873,7 @@ bool AP_Arming::mission_checks(bool report) } RallyLocation rally_loc = {}; if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) { - check_failed(ARMING_CHECK_MISSION, report, "No sufficently close rally point located"); + check_failed(ARMING_CHECK_MISSION, report, "No sufficiently close rally point located"); return false; } #else diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 918bd8256ad135..66577622a7cd40 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -51,7 +51,7 @@ extern const AP_HAL::HAL& hal; // the MSP protocol on hal.console #define BLHELI_UART_LOCK_KEY 0x20180402 -// if no packets are received for this time and motor control is active BLH will disconect (stoping motors) +// if no packets are received for this time and motor control is active BLH will disconnect (stoping motors) #define MOTOR_ACTIVE_TIMEOUT 1000 const AP_Param::GroupInfo AP_BLHeli::var_info[] = { @@ -395,7 +395,7 @@ void AP_BLHeli::msp_process_command(void) break; case MSP_UID: - // MCU identifer + // MCU identifier debug("MSP_UID"); msp_send_reply(msp.cmdMSP, (const uint8_t *)UDID_START, 12); break; @@ -1421,7 +1421,7 @@ void AP_BLHeli::init(uint32_t mask, AP_HAL::RCOutput::output_mode otype) motor_mask = mask; debug("ESC: %u motors mask=0x%08lx", num_motors, mask); - // check if we have a combination of reversable and normal + // check if we have a combination of reversible and normal mixed_type = (mask != (mask & channel_reversible_mask.get())) && (channel_reversible_mask.get() != 0); if (num_motors != 0 && telem_rate > 0) { diff --git a/libraries/AP_BLHeli/AP_BLHeli.h b/libraries/AP_BLHeli/AP_BLHeli.h index 6c00b537bdbb10..ae583262fdaee3 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.h +++ b/libraries/AP_BLHeli/AP_BLHeli.h @@ -237,7 +237,7 @@ class AP_BLHeli : public AP_ESC_Telem_Backend { // have we locked the UART? bool uart_locked; - // true if we have a mix of reversable and normal ESC + // true if we have a mix of reversible and normal ESC bool mixed_type; // mapping from BLHeli motor numbers to RC output channels diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index ebb4af139699bb..f7548894201572 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -530,7 +530,7 @@ float AP_Baro::get_external_temperature(const uint8_t instance) const // The reason for not just using the baro temperature is it tends to read high, // often 30 degrees above the actual temperature. That means the // EAS2TAS tends to be off by quite a large margin, as well as - // the calculation of altitude difference betweeen two pressures + // the calculation of altitude difference between two pressures // reporting a high temperature will cause the aircraft to // estimate itself as flying higher then it actually is. return MIN(get_temperature(instance), INTERNAL_TEMPERATURE_CLAMP); @@ -583,7 +583,7 @@ void AP_Baro::init(void) { init_done = true; - // always set field elvation to zero on reboot in the case user + // always set field elevation to zero on reboot in the case user // fails to update. TBD automate sanity checking error bounds on // on previously saved value at new location etc. if (!is_zero(_field_elevation)) { diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index a1b4b632422951..4b1055fff92213 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -294,7 +294,7 @@ class AP_Baro DerivativeFilterFloat_Size7 _climb_rate_filter; AP_Float _specific_gravity; // the specific gravity of fluid for an ROV 1.00 for freshwater, 1.024 for salt water AP_Float _user_ground_temperature; // user override of the ground temperature used for EAS2TAS - float _guessed_ground_temperature; // currently ground temperature estimate using our best abailable source + float _guessed_ground_temperature; // currently ground temperature estimate using our best available source // when did we last notify the GCS of new pressure reference? uint32_t _last_notify_ms; diff --git a/libraries/AP_Baro/AP_Baro_BMP085.cpp b/libraries/AP_Baro/AP_Baro_BMP085.cpp index 9601db80d2c3cb..d2fed889da6991 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085.cpp @@ -70,7 +70,7 @@ bool AP_Baro_BMP085::_init() // get pointer to i2c bus semaphore AP_HAL::Semaphore *sem = _dev->get_semaphore(); - // take i2c bus sempahore + // take i2c bus semaphore WITH_SEMAPHORE(sem); if (BMP085_EOC >= 0) { @@ -177,7 +177,7 @@ bool AP_Baro_BMP085::_read_prom(uint16_t *prom) } /* - This is a state machine. Acumulate a new sensor reading. + This is a state machine. Accumulate a new sensor reading. */ void AP_Baro_BMP085::_timer(void) { diff --git a/libraries/AP_Baro/AP_Baro_BMP280.cpp b/libraries/AP_Baro/AP_Baro_BMP280.cpp index 005000b169260f..1c89ac0a4b9557 100644 --- a/libraries/AP_Baro/AP_Baro_BMP280.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP280.cpp @@ -127,7 +127,7 @@ bool AP_Baro_BMP280::_init() -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_BMP280::_timer(void) { uint8_t buf[6]; diff --git a/libraries/AP_Baro/AP_Baro_BMP388.cpp b/libraries/AP_Baro/AP_Baro_BMP388.cpp index 25ea7ab41e97bd..6b48d9e7831676 100644 --- a/libraries/AP_Baro/AP_Baro_BMP388.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP388.cpp @@ -130,7 +130,7 @@ bool AP_Baro_BMP388::init() -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_BMP388::timer(void) { uint8_t buf[7]; diff --git a/libraries/AP_Baro/AP_Baro_Backend.cpp b/libraries/AP_Baro/AP_Baro_Backend.cpp index 15c75b65a9228f..f315bcd2b97266 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.cpp +++ b/libraries/AP_Baro/AP_Baro_Backend.cpp @@ -67,7 +67,7 @@ void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float static constexpr float FILTER_KOEF = 0.1f; /* Check that the baro value is valid by using a mean filter. If the - * value is further than filtrer_range from mean value, it is + * value is further than filter_range from mean value, it is * rejected. */ bool AP_Baro_Backend::pressure_ok(float press) diff --git a/libraries/AP_Baro/AP_Baro_Backend.h b/libraries/AP_Baro/AP_Baro_Backend.h index 476473bf5ddef4..94b155e4836bd7 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.h +++ b/libraries/AP_Baro/AP_Baro_Backend.h @@ -20,7 +20,7 @@ class AP_Baro_Backend void backend_update(uint8_t instance); // Check that the baro valid by using a mean filter. - // If the value further that filtrer_range from mean value, it is rejected. + // If the value further that filter_range from mean value, it is rejected. bool pressure_ok(float press); uint32_t get_error_count() const { return _error_count; } diff --git a/libraries/AP_Baro/AP_Baro_DPS280.cpp b/libraries/AP_Baro/AP_Baro_DPS280.cpp index 8eef71f3a71cb1..fe34ca0bd048f0 100644 --- a/libraries/AP_Baro/AP_Baro_DPS280.cpp +++ b/libraries/AP_Baro/AP_Baro_DPS280.cpp @@ -246,7 +246,7 @@ void AP_Baro_DPS280::check_health(void) } } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_DPS280::timer(void) { uint8_t buf[6]; diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index ee1ee9e427ba91..6812480d7a0ef0 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -88,7 +88,7 @@ AP_Baro_DroneCAN* AP_Baro_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_droneca if (create_new) { bool already_detected = false; - //Check if there's an empty spot for possible registeration + //Check if there's an empty spot for possible registration for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { //Already Detected diff --git a/libraries/AP_Baro/AP_Baro_FBM320.cpp b/libraries/AP_Baro/AP_Baro_FBM320.cpp index 20b8edcd710764..7ad9a7b0c89ae6 100644 --- a/libraries/AP_Baro/AP_Baro_FBM320.cpp +++ b/libraries/AP_Baro/AP_Baro_FBM320.cpp @@ -179,7 +179,7 @@ void AP_Baro_FBM320::calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int pressure = ((X31 + X32) >> 15) + PP4 + 99880; } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_FBM320::timer(void) { uint8_t buf[3]; diff --git a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp index 11016e585ab642..6db9acdc3d5447 100644 --- a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp +++ b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp @@ -212,7 +212,7 @@ bool AP_Baro_LPS2XH::_check_whoami(void) return false; } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_LPS2XH::_timer(void) { uint8_t status; diff --git a/libraries/AP_Baro/AP_Baro_SPL06.cpp b/libraries/AP_Baro/AP_Baro_SPL06.cpp index 0ceb27dd955344..baca15dee2d20f 100644 --- a/libraries/AP_Baro/AP_Baro_SPL06.cpp +++ b/libraries/AP_Baro/AP_Baro_SPL06.cpp @@ -179,7 +179,7 @@ int32_t AP_Baro_SPL06::raw_value_scale_factor(uint8_t oversampling) } } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_SPL06::_timer(void) { uint8_t buf[3]; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index b53fb554658698..ca73aab478e86e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -810,7 +810,7 @@ void AP_BattMonitor::check_failsafes(void) #endif state[i].failsafe = type; - // map the desired failsafe action to a prioritiy level + // map the desired failsafe action to a priority level int8_t priority = 0; if (_failsafe_priorities != nullptr) { while (_failsafe_priorities[priority] != -1) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp index 75bbebcae62303..9907a798afcb0d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp @@ -103,7 +103,7 @@ float AP_BattMonitor_Bebop::_filter_voltage(float vbat_raw) _prev_vbat = vbat_raw; only_once = 0; } else if (vbat_raw > 0.0f) { - /* 1st order fitler */ + /* 1st order filter */ vbat = b[0] * vbat_raw + b[1] * _prev_vbat_raw - a[1] * _prev_vbat; _prev_vbat_raw = vbat_raw; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp index f9ee6d2bbf64ae..eb292ea6dea55a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp @@ -32,7 +32,7 @@ bool AP_BattMonitor_Generator_FuelLevel::has_current(void) const return has_consumed_energy(); } -// This is where we tell the battery monitor 'we have consummed energy' if we want to report a fuel level remaining +// This is where we tell the battery monitor 'we have consumed energy' if we want to report a fuel level remaining bool AP_BattMonitor_Generator_FuelLevel::has_consumed_energy(void) const { // Get pointer to generator singleton @@ -149,7 +149,7 @@ AP_BattMonitor::Failsafe AP_BattMonitor_Generator_Elec::update_failsafes() AP_Generator *generator = AP::generator(); - // Only check for failsafes on the electrical moniter + // Only check for failsafes on the electrical monitor // no point in having the same failsafe on two battery monitors if (generator != nullptr) { failsafe = generator->update_failsafes(); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h index bacd1e399a9dd8..db7d17c4b235ca 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h @@ -44,7 +44,7 @@ class AP_BattMonitor_Generator_FuelLevel : public AP_BattMonitor_Backend // This is where we tell the battery monitor 'we have current' if we want to report a fuel level remaining bool has_current(void) const override; - // This is where we tell the battery monitor 'we have consummed energy' if we want to report a fuel level remaining + // This is where we tell the battery monitor 'we have consumed energy' if we want to report a fuel level remaining bool has_consumed_energy(void) const override; }; #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp index 9fc708a9740ed0..2cd58b765b0e27 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp @@ -88,7 +88,7 @@ void AP_BattMonitor_SMBus_Generic::timer() } } - // we loop over something limted by + // we loop over something limited by // BATTMONITOR_SMBUS_NUM_CELLS_MAX but assign into something // limited by AP_BATT_MONITOR_CELLS_MAX - so make sure we won't // over-write: diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp index 591c8fe521f398..4b4af9c5937ad5 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp @@ -57,7 +57,7 @@ void AP_BattMonitor_SMBus_Solo::timer() // accumulate the pack voltage out of the total of the cells // because the Solo's I2C bus is so noisy, it's worth not spending the - // time and bus bandwidth to request the pack voltage as a seperate + // time and bus bandwidth to request the pack voltage as a separate // transaction _state.voltage = pack_voltage_mv * 1e-3f; _state.last_time_micros = tnow; @@ -79,7 +79,7 @@ void AP_BattMonitor_SMBus_Solo::timer() _state.voltage = pack_voltage_mv * 1e-3f; _state.last_time_micros = tnow; _state.healthy = true; - // stop reqesting 4-cell packets. + // stop requesting 4-cell packets. _use_extended = true; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h b/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h index 212ae607bea59e..0a49d0b40538cd 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h @@ -26,6 +26,6 @@ class AP_BattMonitor_Synthetic_Current : public AP_BattMonitor_Analog protected: - AP_Float _max_voltage; /// maximum battery voltage used in current caluculation + AP_Float _max_voltage; /// maximum battery voltage used in current calculation }; #endif diff --git a/libraries/AP_Beacon/AP_Beacon_Nooploop.h b/libraries/AP_Beacon/AP_Beacon_Nooploop.h index e903eb47fb7baa..222c7731492ca5 100644 --- a/libraries/AP_Beacon/AP_Beacon_Nooploop.h +++ b/libraries/AP_Beacon/AP_Beacon_Nooploop.h @@ -33,7 +33,7 @@ class AP_Beacon_Nooploop : public AP_Beacon_Backend // send setting_frame0 to tag. tag will ack setting_frame0 with anchor position filled void request_setting(); - // pase node_frame2 to get tag position and distance + // parse node_frame2 to get tag position and distance void parse_node_frame2(); // parse setting_frame0 to get anchor position diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index 829cbf4123e7bf..799879c2ea7f7c 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -278,7 +278,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { #ifdef HAL_GPIO_PWM_VOLT_PIN // @Param: PWM_VOLT_SEL // @DisplayName: Set PWM Out Voltage - // @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output. On boards with an IOMCU that support this parameter this option only affects the 8 main outputs, not the 6 auxilliary outputs. Using 5V output can help to reduce the impact of ESC noise interference corrupting signals to the ESCs. + // @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output. On boards with an IOMCU that support this parameter this option only affects the 8 main outputs, not the 6 auxiliary outputs. Using 5V output can help to reduce the impact of ESC noise interference corrupting signals to the ESCs. // @Values: 0:3.3V,1:5V // @User: Advanced AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0), diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 596ba0ae3c7c70..78be64a97c66c9 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -442,7 +442,7 @@ void AP_CANManager::handle_can_frame(const mavlink_message_t &msg) buffer_size /= 2; } if (frame_buffer == nullptr) { - // disard the frames + // discard the frames return; } } diff --git a/libraries/AP_CANManager/AP_CANSensor.cpp b/libraries/AP_CANManager/AP_CANSensor.cpp index 91d0fcb724b610..881eb39ce93c8f 100644 --- a/libraries/AP_CANManager/AP_CANSensor.cpp +++ b/libraries/AP_CANManager/AP_CANSensor.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - generic CAN sensor class, for easy creation of CAN sensors using prioprietary protocols + generic CAN sensor class, for easy creation of CAN sensors using proprietary protocols */ #include diff --git a/libraries/AP_CANManager/AP_SLCANIface.cpp b/libraries/AP_CANManager/AP_SLCANIface.cpp index f501e46b397de9..dcd04dcff12f1a 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.cpp +++ b/libraries/AP_CANManager/AP_SLCANIface.cpp @@ -715,7 +715,7 @@ int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time, } } - // We found nothing in HAL's CANIface recieve, so look in SLCANIface + // We found nothing in HAL's CANIface receive, so look in SLCANIface if (_port == nullptr) { return 0; } diff --git a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp index 8041a5fb2c9ce7..06ecf6ee3ae268 100644 --- a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp +++ b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp @@ -6,7 +6,7 @@ // Toggle the shutter on the GoPro // This is so ArduPilot can toggle the shutter directly, either for mission/GCS commands, or when the -// Solo's gimbal is installed on a vehicle other than a Solo. The usual GoPro controls thorugh the +// Solo's gimbal is installed on a vehicle other than a Solo. The usual GoPro controls through the // Solo app and Solo controller do not use this, as it is done offboard on the companion computer. // entry point to actually take a picture. returns true on success bool AP_Camera_SoloGimbal::trigger_pic() diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index 4c9124b6427fc6..86e7dee57c6af8 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = { // @Param: TYPE // @DisplayName: RunCam device type - // @Description: RunCam deviee type used to determine OSD menu structure and shutter options. + // @Description: RunCam device type used to determine OSD menu structure and shutter options. // @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid/RunCam Thumb Pro, 5:Runcam 2 4k AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE), @@ -264,7 +264,7 @@ void AP_RunCam::update_osd() { bool use_armed_state_machine = hal.util->get_soft_armed(); #if OSD_ENABLED - // prevent runcam stick gestures interferring with osd stick gestures + // prevent runcam stick gestures interfering with osd stick gestures if (!use_armed_state_machine) { const AP_OSD* osd = AP::osd(); if (osd != nullptr) { @@ -580,7 +580,7 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev) case Event::IN_MENU_EXIT: // if we are in a sub-menu this will move us out, if we are in the root menu this will - // exit causing the state machine to get out of sync. the OSD menu hierachy is consistently + // exit causing the state machine to get out of sync. the OSD menu hierarchy is consistently // 2 deep so we can count and be reasonably confident of where we are. // the only exception is if someone hits save and exit on the root menu - then we are lost. if (_in_menu > 0) { diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 398656c650be1b..f466e99db23353 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -485,7 +485,7 @@ int32_t Location::diff_longitude(int32_t lon1, int32_t lon2) } /* - limit lattitude to -90e7 to 90e7 + limit latitude to -90e7 to 90e7 */ int32_t Location::limit_lattitude(int32_t lat) { diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 61ed03b78e47a6..134a27e590af36 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -151,7 +151,7 @@ class Location // wrap longitude at -180e7 to 180e7 static int32_t wrap_longitude(int64_t lon); - // limit lattitude to -90e7 to 90e7 + // limit latitude to -90e7 to 90e7 static int32_t limit_lattitude(int32_t lat); // get lon1-lon2, wrapping at -180e7 to 180e7 diff --git a/libraries/AP_Common/tests/test_location.cpp b/libraries/AP_Common/tests/test_location.cpp index f4bef012efc96d..d545c2c754df14 100644 --- a/libraries/AP_Common/tests/test_location.cpp +++ b/libraries/AP_Common/tests/test_location.cpp @@ -371,7 +371,7 @@ TEST(Location, Line) } /* - check if we obey basic euclidian geometry rules of position + check if we obey basic euclidean geometry rules of position addition/subtraction */ TEST(Location, OffsetError) diff --git a/libraries/AP_Common/tests/test_nmea_print.cpp b/libraries/AP_Common/tests/test_nmea_print.cpp index 139e55d6e8c28a..36e62134ef2409 100644 --- a/libraries/AP_Common/tests/test_nmea_print.cpp +++ b/libraries/AP_Common/tests/test_nmea_print.cpp @@ -30,7 +30,7 @@ static DummyUart test_uart; TEST(NMEA, Printf) { - // test not enought space + // test not enough space test_uart.set_txspace(2); EXPECT_FALSE(nmea_printf(&test_uart, "TEST")); // normal test diff --git a/libraries/AP_Compass/AP_Compass_Backend.cpp b/libraries/AP_Compass/AP_Compass_Backend.cpp index bbca45ddb3a9e3..c0a7bf973eeaa1 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.cpp +++ b/libraries/AP_Compass/AP_Compass_Backend.cpp @@ -89,7 +89,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) } #if AP_COMPASS_DIAGONALS_ENABLED - // apply eliptical correction + // apply elliptical correction if (!diagonals.is_zero()) { Matrix3f mat( diagonals.x, offdiagonals.x, offdiagonals.y, @@ -123,7 +123,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) } /* - we apply the motor offsets after we apply the eliptical + we apply the motor offsets after we apply the elliptical correction. This is needed to match the way that the motor compensation values are calculated, as they are calculated based on final field outputs, not on the raw outputs @@ -251,7 +251,7 @@ void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation) static constexpr float FILTER_KOEF = 0.1f; /* Check that the compass value is valid by using a mean filter. If - * the value is further than filtrer_range from mean value, it is + * the value is further than filter_range from mean value, it is * rejected. */ bool AP_Compass_Backend::field_ok(const Vector3f &field) diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 0faae415006f32..779d63f385ec17 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -92,7 +92,7 @@ class AP_Compass_Backend * 2. publish_raw_field - this provides an uncorrected point-sample for * calibration libraries * 3. correct_field - this corrects the measurement in-place for hard iron, - * soft iron, motor interference, and non-orthagonality errors + * soft iron, motor interference, and non-orthogonality errors * 4. publish_filtered_field - legacy filtered magnetic field * * All those functions expect the mag field to be in milligauss. diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 8d70f24c6603bc..ed8f338e549be9 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -464,8 +464,8 @@ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const field = get_field(instance); #if AP_COMPASS_DIAGONALS_ENABLED - // form eliptical correction matrix and invert it. This is - // needed to remove the effects of the eliptical correction + // form elliptical correction matrix and invert it. This is + // needed to remove the effects of the elliptical correction // when calculating new offsets const Vector3f &diagonals = get_diagonals(instance); if (!diagonals.is_zero()) { diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp index 30ad57065141f8..8563dd480bf9bd 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -93,7 +93,7 @@ AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index) bool AP_Compass_DroneCAN::init() { - // Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default + // Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default if (!register_compass(_devid, _instance)) { return false; } @@ -120,7 +120,7 @@ AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_d } bool already_detected = false; - // Check if there's an empty spot for possible registeration + // Check if there's an empty spot for possible registration for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) { if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id && diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index eb304ac9b6a5d2..a9c3d4b10c1e67 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -38,7 +38,7 @@ extern const AP_HAL::HAL& hal; /* - * Defaul address: 0x1E + * Default address: 0x1E */ #define HMC5843_REG_CONFIG_A 0x00 diff --git a/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp b/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp index 92cf47d4421089..d671f3deb5b796 100644 --- a/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp +++ b/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp @@ -70,7 +70,7 @@ AP_Compass_MMC5XX3::AP_Compass_MMC5XX3(AP_HAL::OwnPtr _dev, bool AP_Compass_MMC5XX3::init() { - // take i2c bus sempahore + // take i2c bus semaphore WITH_SEMAPHORE(dev->get_semaphore()); dev->set_retries(10); diff --git a/libraries/AP_Compass/AP_Compass_SITL.cpp b/libraries/AP_Compass/AP_Compass_SITL.cpp index fc0f745287b79c..24687214931081 100644 --- a/libraries/AP_Compass/AP_Compass_SITL.cpp +++ b/libraries/AP_Compass/AP_Compass_SITL.cpp @@ -51,7 +51,7 @@ AP_Compass_SITL::AP_Compass_SITL() /* - create correction matrix for diagnonals and off-diagonals + create correction matrix for diagonals and off-diagonals */ void AP_Compass_SITL::_setup_eliptical_correcion(uint8_t i) { diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 90a3c4e7657aba..3b58159f346ac8 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -241,7 +241,7 @@ class CompassCalibrator { bool _is_external; // true if compass is external (provided by caller) bool _check_orientation; // true if orientation should be automatically checked bool _fix_orientation; // true if orientation should be fixed if necessary - bool _always_45_deg; // true if orentation should considder 45deg with equal tolerance + bool _always_45_deg; // true if orientation should consider 45deg with equal tolerance float _orientation_confidence; // measure of confidence in automatic orientation detection CompassSample _last_sample; diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 8942a6e46d170a..0e4f309fad0b86 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -377,7 +377,7 @@ void AP_DAL::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeSta } -// log wheel odomotry data +// log wheel odometry data void AP_DAL::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius) { end_frame(); @@ -478,22 +478,22 @@ void AP_DAL::handle_message(const log_REVH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) } /* - handle wheel odomotry data + handle wheel odometry data */ void AP_DAL::handle_message(const log_RWOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _RWOH = msg; - // note that EKF2 does not support wheel odomotry + // note that EKF2 does not support wheel odometry ekf3.writeWheelOdom(msg.delAng, msg.delTime, msg.timeStamp_ms, msg.posOffset, msg.radius); } /* - handle body frame odomotry + handle body frame odometry */ void AP_DAL::handle_message(const log_RBOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _RBOH = msg; - // note that EKF2 does not support body frame odomotry + // note that EKF2 does not support body frame odometry ekf3.writeBodyFrameOdom(msg.quality, msg.delPos, msg.delAng, msg.delTime, msg.timeStamp_ms, msg.delay_ms, msg.posOffset); } @@ -503,7 +503,7 @@ void AP_DAL::handle_message(const log_RBOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) void AP_DAL::handle_message(const log_RSLL &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _RSLL = msg; - // note that EKF2 does not support body frame odomotry + // note that EKF2 does not support body frame odometry const Location loc {msg.lat, msg.lng, 0, Location::AltFrame::ABSOLUTE }; ekf3.setLatLng(loc, msg.posAccSD, msg.timestamp_ms); } diff --git a/libraries/AP_DAL/AP_DAL.h b/libraries/AP_DAL/AP_DAL.h index ddf643bcf6e33b..671499b547baa2 100644 --- a/libraries/AP_DAL/AP_DAL.h +++ b/libraries/AP_DAL/AP_DAL.h @@ -215,7 +215,7 @@ class AP_DAL { void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms); void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms); - // log wheel odomotry data + // log wheel odometry data void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius); void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset); diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index d5315e829705e1..4f962574f7a0e7 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -300,7 +300,7 @@ void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg) // Z - Up // https://www.ros.org/reps/rep-0103.html#axis-orientation // As a consequence, to follow ROS REP 103, it is necessary to switch X and Y, - // as well as invert Z (NED to ENU convertion) as well as a 90 degree rotation in the Z axis + // as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis // for x to point forward Quaternion orientation; if (ahrs.get_quaternion(orientation)) { @@ -377,7 +377,7 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) // Z - Up // https://www.ros.org/reps/rep-0103.html#axis-orientation // As a consequence, to follow ROS REP 103, it is necessary to switch X and Y, - // as well as invert Z (NED to ENU convertion) as well as a 90 degree rotation in the Z axis + // as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis // for x to point forward Quaternion orientation; if (ahrs.get_quaternion(orientation)) { diff --git a/libraries/AP_DDS/AP_DDS_External_Odom.cpp b/libraries/AP_DDS/AP_DDS_External_Odom.cpp index cf121f408521a6..8d8563e5e866c3 100644 --- a/libraries/AP_DDS/AP_DDS_External_Odom.cpp +++ b/libraries/AP_DDS/AP_DDS_External_Odom.cpp @@ -27,7 +27,7 @@ void AP_DDS_External_Odom::handle_external_odom(const tf2_msgs_msg_TFMessage& ms convert_transform(ros_transform_stamped.transform, ap_position, ap_rotation); // Although ROS convention states quaternions in ROS messages should be normalized, it's not guaranteed. - // Before propogating a potentially inaccurate quaternion to the rest of AP, normalize it here. + // Before propagating a potentially inaccurate quaternion to the rest of AP, normalize it here. // TODO what if the quaternion is NaN? ap_rotation.normalize(); @@ -38,7 +38,7 @@ void AP_DDS_External_Odom::handle_external_odom(const tf2_msgs_msg_TFMessage& ms // https://www.ros.org/reps/rep-0105.html#id16 // Thus, there will not be any resets. const uint8_t reset_counter {0}; - // TODO imlement jitter correction similar to GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(remote_time_us, sizeof(msg)); + // TODO implement jitter correction similar to GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(remote_time_us, sizeof(msg)); const uint32_t time_ms {static_cast(remote_time_us * 1E-3)}; visual_odom->handle_pose_estimate(remote_time_us, time_ms, ap_position.x, ap_position.y, ap_position.z, ap_rotation, posErr, angErr, reset_counter); diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index f4bad30b966333..f3142c0ca366db 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -84,7 +84,7 @@ While DDS support in Ardupilot is mostly through git submodules, another tool ne ``` > :warning: **If you have installed FastDDS or FastDDSGen globally on your system**: -eProsima's libraries and the packaging system in Ardupilot are not determistic in this scenario. +eProsima's libraries and the packaging system in Ardupilot are not deterministic in this scenario. You may experience the wrong version of a library brought in, or runtime segfaults. For now, avoid having simultaneous local and global installs. If you followed the [global install](https://fast-dds.docs.eprosima.com/en/latest/installation/sources/sources_linux.html#global-installation) @@ -111,7 +111,7 @@ Run the simulator with the following command. If using UDP, the only parameter y | SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | 0 | ```console # Wipe params till you see "AP: ArduPilot Ready" -# Select your favorite vehicle type +# Select your favourite vehicle type sim_vehicle.py -w -v ArduPlane --console -DG --enable-dds # Only set this for Serial, which means 115200 baud @@ -139,7 +139,7 @@ Follow the steps to use the microROS Agent sudo apt install ros-humble-geographic-msgs ``` -- Install and run the microROS agent (as descibed here). Make sure to use the `humble` branch. +- Install and run the microROS agent (as described here). Make sure to use the `humble` branch. - Follow [the instructions](https://micro.ros.org/docs/tutorials/core/first_application_linux/) for the following: - Do "Installing ROS 2 and the micro-ROS build system" @@ -321,7 +321,7 @@ provided a few rules are followed when defining the entries in #### ROS 2 message and service interface types -ROS 2 message and interface defintions are mangled by the `rosidl_adapter` when +ROS 2 message and interface definitions are mangled by the `rosidl_adapter` when mapping from ROS 2 to DDS to avoid naming conflicts in the C/C++ libraries. The ROS 2 object `namespace::Struct` is mangled to `namespace::dds_::Struct_` for DDS. The table below provides some example mappings: diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 05a175e8cfc725..5fe39b57e180db 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -130,7 +130,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Param: ESC_OF // @DisplayName: ESC Output channels offset - // @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth + // @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficient usage of CAN bandwidth // @Range: 0 18 // @User: Advanced AP_GROUPINFO("ESC_OF", 7, AP_DroneCAN, _esc_offset, 0), diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp index 78fb2e55a30fd9..4c87783b1d0e7e 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp @@ -62,7 +62,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() { // Data is parsed directly from the buffer, otherwise we would need to allocate // several hundred bytes for the entire realtime data table or request every - // value individiually + // value individually uint16_t message_length = 0; // reset checksum before reading new data diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index a639e2607e163e..503ef43299dfce 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -87,7 +87,7 @@ class AP_ESC_Telem { // send telemetry data to mavlink void send_esc_telemetry_mavlink(uint8_t mav_chan); - // udpate at 10Hz to log telemetry + // update at 10Hz to log telemetry void update(); // is rpm telemetry configured for the provided channel mask diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index 02a376bbcc3e32..c1769fe2a00a8e 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #include "AP_ExternalAHRS_config.h" diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index 9541db567220e0..89e2331cb86188 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #pragma once diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp index f10c3b2617d962..abdc63250ec587 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp @@ -11,7 +11,7 @@ along with this program. If not, see . */ /* - suppport for MicroStrain CX5/GX5-45 serially connected AHRS Systems + support for MicroStrain CX5/GX5-45 serially connected AHRS Systems */ #define ALLOW_DOUBLE_MATH_FUNCTIONS diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h index 0b0575a608072e..e6b2b9e6bdcb17 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h @@ -11,7 +11,7 @@ along with this program. If not, see . */ /* - suppport for MicroStrain CX5/GX5-45 serially connected AHRS Systems + support for MicroStrain CX5/GX5-45 serially connected AHRS Systems */ #pragma once diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 18a34121b025ee..b7c0bf4bff18cb 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #define ALLOW_DOUBLE_MATH_FUNCTIONS @@ -283,8 +283,8 @@ bool AP_ExternalAHRS_VectorNav::check_uart() return true; } -// Send command to read given register number and wait for responce -// Only run from thread! This blocks until a responce is received +// Send command to read given register number and wait for response +// Only run from thread! This blocks until a response is received #define READ_REQUEST_RETRY_MS 500 void AP_ExternalAHRS_VectorNav::wait_register_responce(const uint8_t register_num) { diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index 183184bf24248f..3ce1fe7f5e2d5d 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #pragma once diff --git a/libraries/AP_ExternalAHRS/MicroStrain_common.cpp b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp index 567ac7d70d3001..d5b723cb125c6a 100644 --- a/libraries/AP_ExternalAHRS/MicroStrain_common.cpp +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp @@ -11,7 +11,7 @@ along with this program. If not, see . */ /* - suppport for MicroStrain CX5/GX5-45 serially connected AHRS Systems + support for MicroStrain CX5/GX5-45 serially connected AHRS Systems */ #define ALLOW_DOUBLE_MATH_FUNCTIONS diff --git a/libraries/AP_ExternalAHRS/MicroStrain_common.h b/libraries/AP_ExternalAHRS/MicroStrain_common.h index 506063b5831e71..37158d7c70dfa4 100644 --- a/libraries/AP_ExternalAHRS/MicroStrain_common.h +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.h @@ -11,7 +11,7 @@ along with this program. If not, see . */ /* - suppport for MicroStrain MIP parsing + support for MicroStrain MIP parsing */ #pragma once diff --git a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp index f728b3362c392c..59cbd357624114 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp @@ -879,7 +879,7 @@ bool AP_Filesystem_FATFS::format(void) #if FF_USE_MKFS WITH_SEMAPHORE(sem); hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FATFS::format_handler, void)); - // the format is handled asyncronously, we inform user of success + // the format is handled asynchronously, we inform user of success // via a text message. format_status can be polled for progress format_status = FormatStatus::PENDING; return true; diff --git a/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp b/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp index f2219e6d7b9ff4..28f296e44647ee 100644 --- a/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp +++ b/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp @@ -56,7 +56,7 @@ static UNUSED_FUNCTION void test_page_program() hal.console->printf("Failed to allocate data for read"); } - // fill program data with its own adress + // fill program data with its own address for (uint32_t i = 0; i < jedec_dev.get_page_size(); i++) { data[i] = i; } diff --git a/libraries/AP_FlashStorage/AP_FlashStorage.cpp b/libraries/AP_FlashStorage/AP_FlashStorage.cpp index a8f99670d6d336..b53960f44bb6d9 100644 --- a/libraries/AP_FlashStorage/AP_FlashStorage.cpp +++ b/libraries/AP_FlashStorage/AP_FlashStorage.cpp @@ -152,7 +152,7 @@ bool AP_FlashStorage::switch_full_sector(void) } // protected_switch_full_sector is protected by switch_full_sector to -// avoid an infinite recursion problem; switch_full_sectory calls +// avoid an infinite recursion problem; switch_full_sector calls // write() which can call switch_full_sector. This has been seen in // practice, and while it might be caused by corruption... corruption // happens. diff --git a/libraries/AP_FlashStorage/AP_FlashStorage.h b/libraries/AP_FlashStorage/AP_FlashStorage.h index b4cb1afd71a890..0f9b6fe3b776e8 100644 --- a/libraries/AP_FlashStorage/AP_FlashStorage.h +++ b/libraries/AP_FlashStorage/AP_FlashStorage.h @@ -236,7 +236,7 @@ class AP_FlashStorage { bool switch_sectors(void) WARN_IF_UNUSED; // _switch_full_sector is protected by switch_full_sector to avoid - // an infinite recursion problem; switch_full_sectory calls + // an infinite recursion problem; switch_full_sector calls // write() which can call switch_full_sector. This has been seen // in practice. bool protected_switch_full_sector(void) WARN_IF_UNUSED; diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index 78e4448064def4..bb7dedc03aae7b 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal; #define AP_FOLLOW_TIMEOUT_MS 3000 // position estimate timeout after 1 second -#define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we haave not heard from them in 10 seconds +#define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we have not heard from them in 10 seconds #define AP_FOLLOW_OFFSET_TYPE_NED 0 // offsets are in north-east-down frame #define AP_FOLLOW_OFFSET_TYPE_RELATIVE 1 // offsets are relative to lead vehicle's heading diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp index 45d4edbbb76c24..90047effd583bc 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp @@ -71,8 +71,8 @@ void AP_Frsky_D::send(void) send_uint16(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360)); // send heading in degree based on AHRS and not GPS calc_gps_position(); if (AP::gps().status() >= 3) { - send_uint16(DATA_ID_GPS_LAT_BP, _SPort_data.latdddmm); // send gps lattitude degree and minute integer part - send_uint16(DATA_ID_GPS_LAT_AP, _SPort_data.latmmmm); // send gps lattitude minutes decimal part + send_uint16(DATA_ID_GPS_LAT_BP, _SPort_data.latdddmm); // send gps latitude degree and minute integer part + send_uint16(DATA_ID_GPS_LAT_AP, _SPort_data.latmmmm); // send gps latitude minutes decimal part send_uint16(DATA_ID_GPS_LAT_NS, _SPort_data.lat_ns); // send gps North / South information send_uint16(DATA_ID_GPS_LONG_BP, _SPort_data.londddmm); // send gps longitude degree and minute integer part send_uint16(DATA_ID_GPS_LONG_AP, _SPort_data.lonmmmm); // send gps longitude minutes decimal part diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp index 26b8b5b2af9732..601c7e98d021f3 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp @@ -20,7 +20,7 @@ void AP_Frsky_MAVlite_SPortToMAVlite::update_checksum(const uint8_t c) } /* - Parses sport packets and if successfull fills the rxmsg mavlite struct + Parses sport packets and if successful fills the rxmsg mavlite struct */ bool AP_Frsky_MAVlite_SPortToMAVlite::process(AP_Frsky_MAVlite_Message &rxmsg, const AP_Frsky_SPort::sport_packet_t &packet) { diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index ca2b518df9e0e8..060fc5ddb8d6ba 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1482,7 +1482,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) ground_speed(0)*100, // cm/s ground_course(0)*100, // 1/100 degrees, num_sats(0), - height_elipsoid_mm, // Elipsoid height in mm + height_elipsoid_mm, // Ellipsoid height in mm hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s @@ -1525,7 +1525,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) state[1].rtk_num_sats, state[1].rtk_age_ms, gps_yaw_cdeg(1), - height_elipsoid_mm, // Elipsoid height in mm + height_elipsoid_mm, // Ellipsoid height in mm hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s @@ -1703,7 +1703,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages() */ bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const { - // always enusre a lag is provided + // always ensure a lag is provided lag_sec = 0.1f; if (instance >= GPS_MAX_INSTANCES) { diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index 52f0cd6c066d07..2471d3958019f4 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -800,7 +800,7 @@ void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len) { // we only handle this if we are the first DroneCAN GPS or we are // using a different uavcan instance than the first GPS, as we - // send the data as broadcast on all DroneCAN devive ports and we + // send the data as broadcast on all DroneCAN device ports and we // don't want to send duplicates const uint32_t now_ms = AP_HAL::millis(); if (_detected_module == 0 || diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index c47828209f94fe..1712f6754bcc57 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -629,7 +629,7 @@ bool AP_GPS_NMEA::_term_complete() // case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC) case _GPS_SENTENCE_VTG + 5: // Speed (VTG) - _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514 + _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximates * 0.514 break; case _GPS_SENTENCE_HDT + 1: // Course (HDT) _new_gps_yaw = _parse_decimal_100(_term); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index e0375d654af122..343587c68e55e5 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -1102,7 +1102,7 @@ AP_GPS_UBLOX::_parse_gps(void) } if(GNSS_GALILEO ==_buffer.gnss.configBlock[i].gnssId) { _buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2); - _buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eigh + _buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eight } } _buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001; diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 300a3bda791943..095bb27366d7a4 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -350,14 +350,14 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float min_dist = MIN(offset_dist, reported_distance); if (offset_dist < minimum_antenna_seperation) { - // offsets have to be sufficently large to get a meaningful angle off of them + // offsets have to be sufficiently large to get a meaningful angle off of them Debug("Insufficent antenna offset (%f, %f, %f)", (double)offset.x, (double)offset.y, (double)offset.z); goto bad_yaw; } if (reported_distance < minimum_antenna_seperation) { - // if the reported distance is less then the minimum seperation it's not sufficently robust - Debug("Reported baseline distance (%f) was less then the minimum antenna seperation (%f)", + // if the reported distance is less then the minimum separation it's not sufficiently robust + Debug("Reported baseline distance (%f) was less then the minimum antenna separation (%f)", (double)reported_distance, (double)minimum_antenna_seperation); goto bad_yaw; } diff --git a/libraries/AP_Generator/AP_Generator.cpp b/libraries/AP_Generator/AP_Generator.cpp index d612d00853e49f..d5cfca045d2d79 100644 --- a/libraries/AP_Generator/AP_Generator.cpp +++ b/libraries/AP_Generator/AP_Generator.cpp @@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_Generator::var_info[] = { // @Param: OPTIONS // @DisplayName: Generator Options // @Description: Bitmask of options for generators - // @Bitmask: 0:Supress Maintenance-Required Warnings + // @Bitmask: 0:Suppress Maintenance-Required Warnings // @User: Standard AP_GROUPINFO("OPTIONS", 2, AP_Generator, _options, 0), @@ -91,7 +91,7 @@ void AP_Generator::init() void AP_Generator::update() { - // Return immediatly if not enabled. Don't support run-time disabling of generator + // Return immediately if not enabled. Don't support run-time disabling of generator if (_driver_ptr == nullptr) { return; } @@ -124,7 +124,7 @@ bool AP_Generator::pre_arm_check(char* failmsg, uint8_t failmsg_len) const return true; } // Don't allow arming if we have disabled the generator since boot - strncpy(failmsg, "Generator disabled, reboot reqired", failmsg_len); + strncpy(failmsg, "Generator disabled, reboot required", failmsg_len); return false; } if (_driver_ptr == nullptr) { diff --git a/libraries/AP_Generator/AP_Generator_Backend.cpp b/libraries/AP_Generator/AP_Generator_Backend.cpp index 99de2363366e9f..6a74ee53e2c245 100644 --- a/libraries/AP_Generator/AP_Generator_Backend.cpp +++ b/libraries/AP_Generator/AP_Generator_Backend.cpp @@ -16,7 +16,7 @@ #if HAL_GENERATOR_ENABLED -// Base class consructor +// Base class constructor AP_Generator_Backend::AP_Generator_Backend(AP_Generator& frontend) : _frontend(frontend) { diff --git a/libraries/AP_Generator/AP_Generator_IE_650_800.h b/libraries/AP_Generator/AP_Generator_IE_650_800.h index 4107f463fd8c3d..94e4c50a2519a0 100644 --- a/libraries/AP_Generator/AP_Generator_IE_650_800.h +++ b/libraries/AP_Generator/AP_Generator_IE_650_800.h @@ -46,7 +46,7 @@ class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell static const uint32_t ERROR_START_UNDER_PRESS = (1U << 19); // (0x80000), Tank pressure < 6 barg static const uint32_t ERROR_TANK_UNDER_PRESS = (1U << 18); // (0x40000), Tank pressure < 5 barg static const uint32_t ERROR_TANK_LOW_PRESS = (1U << 17); // (0x20000), Tank pressure < 15 barg - static const uint32_t ERROR_SAFETY_FLAG = (1U << 16); // (0x10000), Fuel cell's internal saftey flags not set true + static const uint32_t ERROR_SAFETY_FLAG = (1U << 16); // (0x10000), Fuel cell's internal safety flags not set true static const uint32_t ERROR_DENY_START1 = (1U << 15); // (0x8000), Stack 1 denied start static const uint32_t ERROR_DENY_START2 = (1U << 14); // (0x4000), Stack 2 denied start static const uint32_t ERROR_STACK_UT1 = (1U << 13); // (0x2000), Stack 1 under temperature (<5 degC) @@ -74,7 +74,7 @@ class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell | ERROR_START_TIMEOUT // (0x200000), Fuel cell's internal State == start for > 30 s | ERROR_START_UNDER_PRESS // (0x80000), Tank pressure < 6 barg | ERROR_TANK_UNDER_PRESS // (0x40000), Tank pressure < 5 barg - | ERROR_SAFETY_FLAG // (0x10000), Fuel cell's internal saftey flags not set true + | ERROR_SAFETY_FLAG // (0x10000), Fuel cell's internal safety flags not set true | ERROR_DENY_START1 // (0x8000), Stack 1 denied start | ERROR_DENY_START2 // (0x4000), Stack 2 denied start | ERROR_BAT_UV_DENY // (0x400), Battery under voltage (21.6 V) and master denied diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h index 13a852d9a3186c..84395f1125c917 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h @@ -91,7 +91,7 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend // Returns true if a complete sentence was successfully decoded or if the buffer is full. bool decode(char c); - // Unit specific decoding to process characters recieved and build sentence + // Unit specific decoding to process characters received and build sentence virtual void decode_latest_term(void) = 0; // Check if we should notify on any change of fuel cell state diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.cpp b/libraries/AP_Generator/AP_Generator_RichenPower.cpp index c021cbd43ee8da..530f8192b371d5 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.cpp +++ b/libraries/AP_Generator/AP_Generator_RichenPower.cpp @@ -190,7 +190,7 @@ bool AP_Generator_RichenPower::generator_ok_to_run() const constexpr float AP_Generator_RichenPower::heat_required_for_run() { // assume that heat is proportional to RPM. Return a number - // proportial to RPM. Reduce it to account for the cooling some%/s + // proportional to RPM. Reduce it to account for the cooling some%/s // cooling return (45 * IDLE_RPM) * heat_environment_loss_30s; } diff --git a/libraries/AP_Gripper/AP_Gripper.h b/libraries/AP_Gripper/AP_Gripper.h index 29a7c24c447f29..3d412a191a1096 100644 --- a/libraries/AP_Gripper/AP_Gripper.h +++ b/libraries/AP_Gripper/AP_Gripper.h @@ -75,7 +75,7 @@ class AP_Gripper { AP_Int16 grab_pwm; // PWM value sent to Gripper to initiate grabbing the cargo AP_Int16 release_pwm; // PWM value sent to Gripper to release the cargo AP_Int16 neutral_pwm; // PWM value sent to gripper when not grabbing or releasing - AP_Int8 regrab_interval; // Time in seconds that EPM gripper will regrab the cargo to ensure grip has not weakend + AP_Int8 regrab_interval; // Time in seconds that EPM gripper will regrab the cargo to ensure grip has not weakened AP_Float autoclose_time; // Automatic close time (in seconds) AP_Int16 uavcan_hardpoint_id; diff --git a/libraries/AP_Gripper/AP_Gripper_Backend.h b/libraries/AP_Gripper/AP_Gripper_Backend.h index 1607289130a902..1508e0ab1bdeb5 100644 --- a/libraries/AP_Gripper/AP_Gripper_Backend.h +++ b/libraries/AP_Gripper/AP_Gripper_Backend.h @@ -45,7 +45,7 @@ class AP_Gripper_Backend { // grabbed - returns true if currently in grabbed position virtual bool grabbed() const = 0; - // type-specific intiailisations: + // type-specific initialisations: virtual void init_gripper() = 0; // type-specific periodic updates: diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.h b/libraries/AP_Gripper/AP_Gripper_Servo.h index 3c72effc090d3b..e51b729d0b1a9a 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.h +++ b/libraries/AP_Gripper/AP_Gripper_Servo.h @@ -44,7 +44,7 @@ class AP_Gripper_Servo : public AP_Gripper_Backend { protected: - // type-specific intiailisations: + // type-specific initializations: void init_gripper() override; // type-specific periodic updates: diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 9b510a4034b60f..50bcdd8f2f3287 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -362,8 +362,8 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) } } -// sample the gyros either by using a gyro window sampled at the gyro rate or making invdividual samples -// called from fast_loop thread - this function does not take out a sempahore to avoid waiting on the FFT thread +// sample the gyros either by using a gyro window sampled at the gyro rate or making individual samples +// called from fast_loop thread - this function does not take out a semaphore to avoid waiting on the FFT thread void AP_GyroFFT::sample_gyros() { if (!analysis_enabled()) { diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.h b/libraries/AP_GyroFFT/AP_GyroFFT.h index c422372970ef2e..19b501b7193580 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.h +++ b/libraries/AP_GyroFFT/AP_GyroFFT.h @@ -190,7 +190,7 @@ class AP_GyroFFT float update_tl_noise_center_bandwidth_hz(FrequencyPeak peak, uint8_t axis, float value) { return (_thread_state._center_bandwidth_hz_filtered[peak][axis] = _center_bandwidth_filter[peak].apply(axis, value)); } - // write single log mesages + // write single log messages void log_noise_peak(uint8_t id, FrequencyPeak peak) const; // calculate the peak noise frequency void calculate_noise(bool calibrating, const EngineConfig& config); diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index bec7d2ea94324c..027b8f4a07bd12 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -1,5 +1,5 @@ /** - * C preprocesor enumeration of the boards supported by the AP_HAL. + * C preprocessor enumeration of the boards supported by the AP_HAL. * This list exists so HAL_BOARD == HAL_BOARD_xxx preprocessor blocks * can be used to exclude HAL boards from the build when appropriate. * It's not an elegant solution but we can improve it in future. diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index 35a8124d615ee2..b3e84314ed9ef0 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -51,7 +51,7 @@ namespace AP_HAL { /* Typdefs for function pointers (Procedure, Member Procedure) For member functions we use the FastDelegate delegates class - which allows us to encapculate a member function as a type + which allows us to encapsulate a member function as a type */ typedef void(*Proc)(void); FUNCTOR_TYPEDEF(MemberProc, void); diff --git a/libraries/AP_HAL/CANIface.h b/libraries/AP_HAL/CANIface.h index ad8a0ead3597cc..06b4f7dffbf848 100644 --- a/libraries/AP_HAL/CANIface.h +++ b/libraries/AP_HAL/CANIface.h @@ -179,7 +179,7 @@ class AP_HAL::CANIface // fill read select with true if a frame is available in Rx buffer // fill write select with true if space is available in Tx buffer // Also waits for Rx or Tx event depending on read_select and write_select values - // passed to the method until timeout. Returns true if the Rx/Tx even occured + // passed to the method until timeout. Returns true if the Rx/Tx even occurred // while waiting, false if timedout virtual bool select(bool &read_select, bool &write_select, const CANFrame* const pending_tx, uint64_t timeout) @@ -192,11 +192,11 @@ class AP_HAL::CANIface return true; } - // Put frame in queue to be sent, return negative if error occured, 0 if no space, and 1 if successful + // Put frame in queue to be sent, return negative if error occurred, 0 if no space, and 1 if successful // must be called on child class virtual int16_t send(const CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags); - // Non blocking receive frame that pops the frames received inside the buffer, return negative if error occured, + // Non blocking receive frame that pops the frames received inside the buffer, return negative if error occurred, // 0 if no frame available, 1 if successful // must be called on child class virtual int16_t receive(CANFrame& out_frame, uint64_t& out_ts_monotonic, CanIOFlags& out_flags); diff --git a/libraries/AP_HAL/Device.cpp b/libraries/AP_HAL/Device.cpp index beedb242212b34..8f80bf4bff9fa8 100644 --- a/libraries/AP_HAL/Device.cpp +++ b/libraries/AP_HAL/Device.cpp @@ -30,7 +30,7 @@ Periodically (say at 50Hz) you should then call check_next_register(). If that returns false then the sensor has had a corrupted register value. Marking the sensor as unhealthy is - approriate. The bad value will be corrected + appropiate. The bad value will be corrected */ /* diff --git a/libraries/AP_HAL/GPIO.h b/libraries/AP_HAL/GPIO.h index 5dbd7530149645..f32a1eb250ede4 100644 --- a/libraries/AP_HAL/GPIO.h +++ b/libraries/AP_HAL/GPIO.h @@ -82,7 +82,7 @@ class AP_HAL::GPIO { // ret indicates the functor must return void // pin is the pin which has triggered the interrupt // state is the new state of the pin - // timestamp is the time in microseconds the interrupt occured + // timestamp is the time in microseconds the interrupt occurred FUNCTOR_TYPEDEF(irq_handler_fn_t, void, uint8_t, bool, uint32_t); virtual bool attach_interrupt(uint8_t pin, irq_handler_fn_t fn, diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index f4ffd25f5aa922..366b13963a481d 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -332,7 +332,7 @@ class AP_HAL::RCOutput { const static uint32_t ALL_CHANNELS = 255; /* - Send a dshot command, if command timout is 0 then 10 commands are sent + Send a dshot command, if command timeout is 0 then 10 commands are sent chan is the servo channel to send the command to */ virtual void send_dshot_command(uint8_t command, uint8_t chan = ALL_CHANNELS, uint32_t command_timeout_ms = 0, uint16_t repeat_count = 10, bool priority = false) {} diff --git a/libraries/AP_HAL/WSPIDevice.h b/libraries/AP_HAL/WSPIDevice.h index 08c93f4bfe4856..1b4c3a294c5f7e 100644 --- a/libraries/AP_HAL/WSPIDevice.h +++ b/libraries/AP_HAL/WSPIDevice.h @@ -143,7 +143,7 @@ class WSPIDevice : public Device virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override = 0; - // Set command header for upcomming transfer call(s) + // Set command header for upcoming transfer call(s) virtual void set_cmd_header(const CommandHeader& cmd_hdr) override = 0; virtual bool is_busy() = 0; diff --git a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp index 33689a8fdd2e63..1a177b13bb55b0 100644 --- a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp +++ b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp @@ -22,7 +22,7 @@ void loop(); //declaration of the loop() function const AP_HAL::HAL& hal = AP_HAL::get_HAL(); //create a reference to AP_HAL::HAL object to get access to hardware specific functions. For more info see -AP_HAL::AnalogSource* chan; //delare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h +AP_HAL::AnalogSource* chan; //declare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h // the setup function runs once when the board powers up void setup(void) { diff --git a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp index ff6e57cb652044..ca8dd7b0b086cc 100644 --- a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp +++ b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp @@ -28,12 +28,12 @@ void drive(uint16_t hz_speed); class Menu_Commands { public: /* Menu commands to drive a SERVO type with - * repective PWM output freq defined by SERVO_HZ + * respective PWM output freq defined by SERVO_HZ */ int8_t menu_servo(uint8_t argc, const Menu::arg *argv); /* Menu commands to drive a ESC type with - * repective PWM output freq defined by ESC_HZ + * respective PWM output freq defined by ESC_HZ */ int8_t menu_esc(uint8_t argc, const Menu::arg *argv); }; @@ -45,7 +45,7 @@ Menu_Commands commands; static uint16_t pwm = 1500; static int8_t delta = 1; -/* Function to drive a RC output TYPE especified */ +/* Function to drive a RC output TYPE specified */ void drive(uint16_t hz_speed) { hal.rcout->set_freq(0xFF, hz_speed); diff --git a/libraries/AP_HAL/examples/Storage/Storage.cpp b/libraries/AP_HAL/examples/Storage/Storage.cpp index 171c423de5b39d..e39fd83b1af27b 100644 --- a/libraries/AP_HAL/examples/Storage/Storage.cpp +++ b/libraries/AP_HAL/examples/Storage/Storage.cpp @@ -20,7 +20,7 @@ void setup(void) st->init(); /* - Calculate XOR of the full conent of memory + Calculate XOR of the full content of memory Do it by block of 8 bytes */ unsigned char buff[8], XOR_res = 0; @@ -35,7 +35,7 @@ void setup(void) /* print XORed result */ - hal.console->printf("XORed ememory: %u\r\n", (unsigned) XOR_res); + hal.console->printf("XORed memory: %u\r\n", (unsigned) XOR_res); } // In main loop do nothing diff --git a/libraries/AP_HAL/utility/ftoa_engine.cpp b/libraries/AP_HAL/utility/ftoa_engine.cpp index 384f32c2afd25e..e2800529082c56 100644 --- a/libraries/AP_HAL/utility/ftoa_engine.cpp +++ b/libraries/AP_HAL/utility/ftoa_engine.cpp @@ -131,7 +131,7 @@ int16_t ftoa_engine(float val, char *buf, uint8_t precision, uint8_t maxDecimals int64_t prod = (int64_t)frac * (int64_t)factorTable[idx]; // The expConvFactorTable are factor are correct iff the lower 3 exponent - // bits are 1 (=7). Else we need to compensate by divding frac. + // bits are 1 (=7). Else we need to compensate by dividing frac. // If the lower 3 bits are 7 we are right. // If the lower 3 bits are 6 we right-shift once // .. diff --git a/libraries/AP_HAL/utility/srxl.cpp b/libraries/AP_HAL/utility/srxl.cpp index 1023daa427d34c..14b4e211974b60 100644 --- a/libraries/AP_HAL/utility/srxl.cpp +++ b/libraries/AP_HAL/utility/srxl.cpp @@ -17,7 +17,7 @@ Andrew Tridgell, September 2016 Co author: Roman Kirchner, September 2016 - - 2016.10.23: SRXL variant V1 sucessfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26) + - 2016.10.23: SRXL variant V1 successfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26) */ #include "srxl.h" @@ -49,7 +49,7 @@ #define SRXL_HEADER_V1 0xA1U /* Headerbyte for: Mpx SRXLv1 or XBUS Mode B */ #define SRXL_HEADER_V2 0xA2U /* Headerbyte for: Mpx SRXLv2 */ #define SRXL_HEADER_V5 0xA5U /* Headerbyte for: Spk AR7700 etc. */ -#define SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non impemented srxl header*/ +#define SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non implemented srxl header*/ diff --git a/libraries/AP_HAL/utility/st24.cpp b/libraries/AP_HAL/utility/st24.cpp index 80c8643d726671..04cad551020c51 100644 --- a/libraries/AP_HAL/utility/st24.cpp +++ b/libraries/AP_HAL/utility/st24.cpp @@ -125,7 +125,7 @@ typedef struct { */ typedef struct { uint16_t t; ///< packet counter or clock - int32_t lat; ///< lattitude (degrees) +/- 90 deg + int32_t lat; ///< latitude (degrees) +/- 90 deg int32_t lon; ///< longitude (degrees) +/- 180 deg int32_t alt; ///< 0.01m resolution, altitude (meters) int16_t vx, vy, vz; ///< velocity 0.01m res, +/-320.00 North-East- Down diff --git a/libraries/AP_HAL/utility/sumd.h b/libraries/AP_HAL/utility/sumd.h index 22052a20bab877..2c27a310a0dce1 100644 --- a/libraries/AP_HAL/utility/sumd.h +++ b/libraries/AP_HAL/utility/sumd.h @@ -50,7 +50,7 @@ * * @param byte current char to read * @param rssi pointer to a byte where the RSSI value is written back to - * @param rx_count pointer to a byte where the receive count of packets signce last wireless frame is written back to + * @param rx_count pointer to a byte where the receive count of packets since last wireless frame is written back to * @param channels pointer to a datastructure of size max_chan_count where channel values (12 bit) are written back to * @param max_chan_count maximum channels to decode - if more channels are decoded, the last n are skipped and success (0) is returned * @return 0 for success (a decoded packet), 1 for no packet yet (accumulating), 2 for unknown packet, 3 for out of sync, 4 for checksum error