diff --git a/ArduCopter/control_auto.cpp b/ArduCopter/control_auto.cpp index 36a0e30066..b07bcd6abe 100644 --- a/ArduCopter/control_auto.cpp +++ b/ArduCopter/control_auto.cpp @@ -23,7 +23,7 @@ bool Copter::auto_init(bool ignore_checks) if ((position_ok() && mission.num_commands() > 1) || ignore_checks) { auto_mode = Auto_Loiter; - // reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce change of flips) + // reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips) if (motors.armed() && ap.land_complete && !mission.starts_with_takeoff_cmd()) { gcs_send_text(MAV_SEVERITY_CRITICAL, "Auto: Missing Takeoff Cmd"); return false; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 28c6d92fd3..de2bef937b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -18,7 +18,7 @@ #define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS radians(720.0f) // maximum body-frame acceleration limit for the stability controller (for roll and pitch axis) #define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS radians(10.0f) // minimum body-frame acceleration limit for the stability controller (for yaw axis) #define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS radians(120.0f) // maximum body-frame acceleration limit for the stability controller (for yaw axis) -#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS 6000 // constraint on yaw angle error in degrees. This should lead to maximum turn rate of 10deg/sed * Stab Rate P so by default will be 45deg/sec. +#define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS 6000 // constraint on yaw angle error in degrees. This should lead to maximum turn rate of 10deg/sec * Stab Rate P so by default will be 45deg/sec. #define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS 110000.0f // default maximum acceleration for roll/pitch axis in centidegrees/sec/sec #define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS 27000.0f // default maximum acceleration for yaw axis in centidegrees/sec/sec @@ -143,7 +143,7 @@ public: // Return 321-intrinsic euler angles in centidegrees representing the rotation from NED earth frame to the // attitude controller's target attitude. // **NOTE** Using vector3f*deg(100) is more efficient than deg(vector3f)*100 or deg(vector3d*100) because it gives the - // same result with the fewest multiplcations. Even though it may look like a bug, it is intentional. See issue 4895. + // same result with the fewest multiplications. Even though it may look like a bug, it is intentional. See issue 4895. Vector3f get_att_target_euler_cd() const { return _attitude_target_euler_angle*degrees(100.0f); } // Return the angle between the target thrust vector and the current thrust vector. diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index c44938b35c..7dd702eb70 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -37,8 +37,8 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @User: Standard // @Param: RAT_RLL_FILT - // @DisplayName: Roll axis rate conroller input frequency in Hz - // @Description: Roll axis rate conroller input frequency in Hz + // @DisplayName: Roll axis rate controller input frequency in Hz + // @Description: Roll axis rate controller input frequency in Hz // @Range: 1 100 // @Increment: 1 // @Units: Hz @@ -75,8 +75,8 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @User: Standard // @Param: RAT_PIT_FILT - // @DisplayName: Pitch axis rate conroller input frequency in Hz - // @Description: Pitch axis rate conroller input frequency in Hz + // @DisplayName: Pitch axis rate controller input frequency in Hz + // @Description: Pitch axis rate controller input frequency in Hz // @Range: 1 100 // @Increment: 1 // @Units: Hz @@ -113,8 +113,8 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @User: Standard // @Param: RAT_YAW_FILT - // @DisplayName: Yaw axis rate conroller input frequency in Hz - // @Description: Yaw axis rate conroller input frequency in Hz + // @DisplayName: Yaw axis rate controller input frequency in Hz + // @Description: Yaw axis rate controller input frequency in Hz // @Range: 1 100 // @Increment: 1 // @Units: Hz diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index dda5fb249a..f2ca001970 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -56,7 +56,7 @@ public: enum xy_mode { XY_MODE_POS_ONLY = 0, // position correction only (i.e. no velocity feed-forward) XY_MODE_POS_LIMITED_AND_VEL_FF, // for loiter - rate-limiting the position correction, velocity feed-forward - XY_MODE_POS_AND_VEL_FF // for velocity controller - unlimied position correction, velocity feed-forward + XY_MODE_POS_AND_VEL_FF // for velocity controller - unlimited position correction, velocity feed-forward }; /// diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index 46baf7236b..998dd02ab1 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -15,7 +15,7 @@ const AP_Param::GroupInfo AC_Sprayer::var_info[] = { // @Param: PUMP_RATE // @DisplayName: Pump speed - // @Description: Desired pump speed when travelling 1m/s expressed as a percentage + // @Description: Desired pump speed when traveling 1m/s expressed as a percentage // @Units: percentage // @Range: 0 100 // @User: Standard @@ -152,7 +152,7 @@ AC_Sprayer::update() _speed_over_min_time = 0; } - // if testing pump output speed as if travelling at 1m/s + // if testing pump output speed as if traveling at 1m/s if (_flags.testing) { ground_speed = 100.0f; should_be_spraying = true; diff --git a/libraries/AC_WPNav/AC_Circle.h b/libraries/AC_WPNav/AC_Circle.h index 21fad2f9f9..107ff7338f 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -93,7 +93,7 @@ private: Vector3f _center; // center of circle in cm from home 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 travelled in radians + float _angle_total; // total angle traveled 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/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 47df8837ea..f2a9789217 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -68,7 +68,7 @@ public: // dead-reckoning support bool get_position(struct Location &loc) const; - // get latest altitude estimate above ground level in metres and validity flag + // get latest altitude estimate above ground level in meters and validity flag bool get_hagl(float &hagl) const; // status reporting of estimated error @@ -138,13 +138,13 @@ public: bool get_relative_position_D(float &posD) const; // Get a derivative of the vertical position in m/s 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 get_vert_pos_rate(float &velocity); // write optical flow measurements to EKF void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset); - // inibit GPS usage + // inhibit GPS usage uint8_t setInhibitGPS(void); // get speed limit @@ -172,11 +172,11 @@ public: // returns the time of the last yaw angle reset or 0 if no reset has ever occurred uint32_t getLastYawResetAngle(float &yawAng) const; - // return the amount of NE position change in metres due to the last reset + // return the amount of NE position change in meters due to the last reset // returns the time of the last reset or 0 if no reset has ever occurred uint32_t getLastPosNorthEastReset(Vector2f &pos) const; - // return the amount of NE velocity change in metres/sec due to the last reset + // return the amount of NE velocity change in meters/sec due to the last reset // returns the time of the last reset or 0 if no reset has ever occurred uint32_t getLastVelNorthEastReset(Vector2f &vel) const; @@ -194,7 +194,7 @@ public: // send a EKF_STATUS_REPORT for current EKF void send_ekf_status_report(mavlink_channel_t chan); - // get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag + // get_hgt_ctrl_limit - get maximum height to be observed by the control loops in meters and a validity flag // this is used to limit height during optical flow navigation // it will return invalid when no limiting is required bool get_hgt_ctrl_limit(float &limit) const; @@ -204,8 +204,8 @@ public: bool get_location(struct Location &loc) 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 of 1 is the maximum - // inconsistency that will be accpeted by the filter + // indicates perfect consistency between the measurement and the EKF solution and a value of of 1 is the maximum + // inconsistency that will be accepted by the filter // boolean false is returned if variances are not available bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override; diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index e16dbaddb9..11867f255d 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -97,7 +97,7 @@ char (&_ARRAY_SIZE_HELPER(T (&_arr)[0]))[0]; /// /// Data structures and types used throughout the libraries and applications. 0 = default /// bit 0: Altitude is stored 0: Absolute, 1: Relative -/// bit 1: Chnage Alt between WP 0: Gradually, 1: ASAP +/// bit 1: Change Alt between WP 0: Gradually, 1: ASAP /// bit 2: Direction of loiter command 0: Clockwise 1: Counter-Clockwise /// bit 3: Req.to hit WP.alt to continue 0: No, 1: Yes /// bit 4: Relative to Home 0: No, 1: Yes @@ -125,7 +125,7 @@ struct PACKED Location { // allowing an accurate angle in centi-degrees. This keeps the // storage cost per mission item at 15 bytes, and allows mission // altitudes of up to +/- 83km - int32_t alt:24; ///< param 2 - Altitude in centimeters (meters * 100) + int32_t alt:24; ///< param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M int32_t lat; ///< param 3 - Latitude * 10**7 int32_t lng; ///< param 4 - Longitude * 10**7 }; diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index fa1905f9d9..3c7ca907e4 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -269,7 +269,7 @@ AP_GPS::detect_instance(uint8_t instance) switch (_type[instance]) { #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 case GPS_TYPE_PX4: - // check for explicitely chosen PX4 GPS beforehand + // check for explicitly chosen PX4 GPS beforehand // it is not possible to autodetect it, nor does it require a real UART _broadcast_gps_type("PX4", instance, -1); // baud rate isn't valid new_gps = new AP_GPS_PX4(*this, state[instance], _port[instance]); diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index e2342b0b0c..093960f6ec 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -26,7 +26,7 @@ /** maximum number of GPS instances available on this platform. If more - than 1 then redundent sensors may be available + than 1 then redundant sensors may be available */ #define GPS_MAX_INSTANCES 2 #define GPS_RTK_INJECT_TO_ALL 127 @@ -312,7 +312,7 @@ public: // the expected lag (in seconds) in the position and velocity readings from the gps float get_lag() const { return 0.2f; } - // return a 3D vector defining the offset of the GPS antenna in metres relative to the body frame origin + // return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin const Vector3f &get_antenna_offset(uint8_t instance) const { return _antenna_offset[instance]; } @@ -444,7 +444,7 @@ private: // re-assemble GPS_RTCM_DATA message void handle_gps_rtcm_data(const mavlink_message_t *msg); - // ibject data into all backends + // inject data into all backends void inject_data_all(const uint8_t *data, uint16_t len); }; diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index af648ae3b5..e109c78116 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -38,7 +38,7 @@ void AP_InertialNav_NavEKF::update(float dt) } // 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. if (_ahrs_ekf.get_vert_pos_rate(_pos_z_rate)) { _pos_z_rate *= 100; // convert to cm/s _pos_z_rate = - _pos_z_rate; // InertialNav is NEU diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index af3b63c780..013175ae41 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -797,7 +797,7 @@ void NavEKF2::getVelNED(int8_t instance, Vector3f &vel) } } -// Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s +// Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s float NavEKF2::getPosDownDerivative(int8_t instance) { if (instance < 0 || instance >= num_cores) instance = primary; @@ -986,7 +986,7 @@ bool NavEKF2::getOriginLLH(struct Location &loc) const } // set the latitude and longitude and height used to set the NED origin -// All NED positions calcualted by the filter will be relative to this location +// All NED positions calculated by the filter will be relative to this location // The origin cannot be set if the filter is in a flight mode (eg vehicle armed) // Returns false if the filter has rejected the attempt to set the origin bool NavEKF2::setOriginLLH(struct Location &loc) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 3e426d5b7d..c3f830c4b9 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -137,14 +137,14 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = { // @User: Advanced AP_GROUPINFO("2_TYPE", 16, AP_Proximity, _type[1], 0), - // @Param: _ORIENT + // @Param: 2_ORIENT // @DisplayName: Second Proximity sensor orientation // @Description: Second Proximity sensor orientation // @Values: 0:Default,1:Upside Down // @User: Standard AP_GROUPINFO("2_ORIENT", 17, AP_Proximity, _orientation[1], 0), - // @Param: _YAW_CORR + // @Param: 2_YAW_CORR // @DisplayName: Second Proximity sensor yaw correction // @Description: Second Proximity sensor yaw correction // @Range: -180 180 diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e89507c009..4939235737 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1607,7 +1607,7 @@ void GCS_MAVLINK::send_local_position(const AP_AHRS &ahrs) const } /* - send LOCAL_POSITION_NED message + send VIBRATION message */ void GCS_MAVLINK::send_vibration(const AP_InertialSensor &ins) const {