Spelling errors (#19935)

This commit is contained in:
Hamish Willee
2022-07-27 14:33:16 +10:00
committed by GitHub
parent 97f632a408
commit e6eed43648
97 changed files with 170 additions and 158 deletions
+1 -1
View File
@@ -1063,7 +1063,7 @@ PARAM_DEFINE_FLOAT(COM_WIND_WARN, -1.f);
* the time since takeoff is above this value. It is not possible to resume the
* mission or switch to any mode other than RTL or Land.
*
* Set a nagative value to disable.
* Set a negative value to disable.
*
*
* @unit s
+2 -2
View File
@@ -479,7 +479,7 @@ union filter_control_status_u {
uint32_t gps : 1; ///< 2 - true if GPS measurement fusion is intended
uint32_t opt_flow : 1; ///< 3 - true if optical flow measurements fusion is intended
uint32_t mag_hdg : 1; ///< 4 - true if a simple magnetic yaw heading fusion is intended
uint32_t mag_3D : 1; ///< 5 - true if 3-axis magnetometer measurement fusion is inteded
uint32_t mag_3D : 1; ///< 5 - true if 3-axis magnetometer measurement fusion is intended
uint32_t mag_dec : 1; ///< 6 - true if synthetic magnetic declination measurements fusion is intended
uint32_t in_air : 1; ///< 7 - true when the vehicle is airborne
uint32_t wind : 1; ///< 8 - true when wind velocity is being estimated
@@ -571,7 +571,7 @@ union warning_event_status_u {
bool height_sensor_timeout : 1; ///< 4 - true when the height sensor has not been used to correct the state estimates for a significant time period
bool stopping_navigation : 1; ///< 5 - true when the filter has insufficient data to estimate velocity and position and is falling back to an attitude, height and height rate mode of operation
bool invalid_accel_bias_cov_reset : 1; ///< 6 - true when the filter has detected bad acceerometer bias state estimates and has reset the corresponding covariance matrix elements
bool bad_yaw_using_gps_course : 1; ///< 7 - true when the fiter has detected an invalid yaw esitmate and has reset the yaw angle to the GPS ground course
bool bad_yaw_using_gps_course : 1; ///< 7 - true when the filter has detected an invalid yaw estimate and has reset the yaw angle to the GPS ground course
bool stopping_mag_use : 1; ///< 8 - true when the filter has detected bad magnetometer data and is stopping further use of the magnetomer data
bool vision_data_stopped : 1; ///< 9 - true when the vision system data has stopped for a significant time period
bool emergency_yaw_reset_mag_stopped : 1; ///< 10 - true when the filter has detected bad magnetometer data, has reset the yaw to anothter source of data and has stopped further use of the magnetomer data
+1 -1
View File
@@ -1539,7 +1539,7 @@ void EKF2::UpdateAirspeedSample(ekf2_timestamps_s &ekf2_timestamps)
void EKF2::UpdateAuxVelSample(ekf2_timestamps_s &ekf2_timestamps)
{
// EKF auxillary velocity sample
// EKF auxiliary velocity sample
// - use the landing target pose estimate as another source of velocity data
const unsigned last_generation = _landing_target_pose_sub.get_last_generation();
landing_target_pose_s landing_target_pose;
+1 -1
View File
@@ -358,7 +358,7 @@ private:
(ParamExtFloat<px4::params::EKF2_EV_DELAY>)
_param_ekf2_ev_delay, ///< off-board vision measurement delay relative to the IMU (mSec)
(ParamExtFloat<px4::params::EKF2_AVEL_DELAY>)
_param_ekf2_avel_delay, ///< auxillary velocity measurement delay relative to the IMU (mSec)
_param_ekf2_avel_delay, ///< auxiliary velocity measurement delay relative to the IMU (mSec)
(ParamExtFloat<px4::params::EKF2_GYR_NOISE>)
_param_ekf2_gyr_noise, ///< IMU angular rate noise used for covariance prediction (rad/sec)
+5 -5
View File
@@ -139,7 +139,7 @@ PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 100);
PARAM_DEFINE_FLOAT(EKF2_EV_DELAY, 0);
/**
* Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements
* Auxiliary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements
*
* @group EKF2
* @min 0
@@ -676,7 +676,7 @@ PARAM_DEFINE_INT32(EKF2_NOAID_TOUT, 5000000);
PARAM_DEFINE_FLOAT(EKF2_RNG_NOISE, 0.1f);
/**
* Range finder range dependant noise scaler.
* Range finder range dependent noise scaler.
*
* Specifies the increase in range finder noise with range.
*
@@ -702,7 +702,7 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_GATE, 5.0f);
/**
* Expected range finder reading when on ground.
*
* If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.
* If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.
*
* @group EKF2
* @min 0.01
@@ -1374,7 +1374,7 @@ PARAM_DEFINE_INT32(EKF2_MAG_CHECK, 1);
* For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated
* using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter
* will only have an effect if the global position of the drone is known.
* For 3D mag fusion the magnetometer Z measurement will simply be ingored instead of fusing the synthetic value.
* For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.
*
* @group EKF2
* @boolean
@@ -1384,7 +1384,7 @@ PARAM_DEFINE_INT32(EKF2_SYNT_MAG_Z, 0);
/**
* Default value of true airspeed used in EKF-GSF AHRS calculation.
*
* If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.
* If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.
*
* @group EKF2
* @min 0.0
@@ -385,7 +385,7 @@ void FlightModeManager::handleCommand()
// check what command it is
FlightTaskIndex desired_task = switchVehicleCommand(command.command);
// ignore all unkown commands
// ignore all unknown commands
if (desired_task != FlightTaskIndex::None
&& _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
// switch to the commanded task
@@ -91,7 +91,7 @@ upperCase = lambda s: s[:].upper() if s else ''
@[end for]@
@[end if]@
// ignore all unkown commands
// ignore all unknown commands
default : return FlightTaskIndex::None;
}
}
@@ -197,7 +197,7 @@ private:
_triplet_next_wp; /**< next triplet from navigator which may differ from the intenal one (_next_wp) depending on the vehicle state.*/
matrix::Vector3f _closest_pt; /**< closest point to the vehicle position on the line previous - target */
hrt_abstime _time_last_cruise_speed_override{0}; ///< timestamp the cruise speed was last time overriden using DO_CHANGE_SPEED
hrt_abstime _time_last_cruise_speed_override{0}; ///< timestamp the cruise speed was last time overridden using DO_CHANGE_SPEED
MapProjection _reference_position{}; /**< Class used to project lat/lon setpoint into local frame. */
float _reference_altitude{NAN}; /**< Altitude relative to ground. */
@@ -99,7 +99,7 @@ PARAM_DEFINE_FLOAT(FLW_TGT_FA, 180.0f);
* to prevent terrain collisions due to GPS inaccuracies of the target.
*
* @value 0 2D Tracking: Maintain constant altitude relative to home and track XY position only
* @value 1 2D + Terrain: Mantain constant altitude relative to terrain below and track XY position
* @value 1 2D + Terrain: Maintain constant altitude relative to terrain below and track XY position
* @value 2 3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)
* @group Follow target
*/
@@ -85,7 +85,7 @@ protected:
(ParamFloat<px4::params::MPC_MAN_Y_TAU>) _param_mpc_man_y_tau,
(ParamFloat<px4::params::MPC_MAN_TILT_MAX>) _param_mpc_man_tilt_max, /**< maximum tilt allowed for manual flight */
(ParamFloat<px4::params::MPC_LAND_ALT1>) _param_mpc_land_alt1, /**< altitude at which to start downwards slowdown */
(ParamFloat<px4::params::MPC_LAND_ALT2>) _param_mpc_land_alt2, /**< altitude below wich to land with land speed */
(ParamFloat<px4::params::MPC_LAND_ALT2>) _param_mpc_land_alt2, /**< altitude below which to land with land speed */
(ParamFloat<px4::params::MPC_LAND_SPEED>)
_param_mpc_land_speed, /**< desired downwards speed when approaching the ground */
(ParamFloat<px4::params::MPC_TKO_SPEED>)
@@ -52,7 +52,7 @@ FlightTaskOrbit::FlightTaskOrbit()
bool FlightTaskOrbit::applyCommandParameters(const vehicle_command_s &command)
{
bool ret = true;
// save previous velocity and roatation direction
// save previous velocity and rotation direction
bool new_is_clockwise = _orbit_velocity > 0;
float new_radius = _orbit_radius;
float new_absolute_velocity = fabsf(_orbit_velocity);
@@ -46,7 +46,7 @@
* and can be dangerous. Only activate if you know what you
* are doing, and in a safe environment.
*
* Any motion of the remote stick will abord the signal
* Any motion of the remote stick will abort the signal
* injection and reset this parameter
* Best is to perform the identification in position or
* hold mode.
@@ -76,7 +76,7 @@ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
/**
* L1 controller roll slew rate limit.
*
* The maxium change in roll angle setpoint per second.
* The maximum change in roll angle setpoint per second.
*
* @unit deg/s
* @min 0
@@ -826,7 +826,7 @@ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f);
PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f);
/**
* RC stick configuraton fixed-wing.
* RC stick configuration fixed-wing.
*
* Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight.
*
@@ -7916,7 +7916,7 @@ typedef struct
const float32_t *dualCoefficients; /**< Dual coefficients */
const float32_t *supportVectors; /**< Support vectors */
const int32_t *classes; /**< The two SVM classes */
float32_t coef0; /**< Independant constant */
float32_t coef0; /**< Independent constant */
float32_t gamma; /**< Gamma factor */
} arm_svm_sigmoid_instance_f32;
@@ -210,7 +210,7 @@ void BlockLocalPositionEstimator::gpsCorrect()
// fault detection
float beta = (r.transpose() * (S_I * r))(0, 0);
// artifically increase beta threshhold to prevent fault during landing
// artificially increase beta threshhold to prevent fault during landing
float beta_thresh = 1e2f;
if (beta / BETA_TABLE[n_y_gps] > beta_thresh) {
@@ -67,7 +67,7 @@ void BlockLocalPositionEstimator::landCorrect()
// fault detection
float beta = (r.transpose() * (S_I * r))(0, 0);
// artifically increase beta threshhold to prevent fault during landing
// artificially increase beta threshhold to prevent fault during landing
float beta_thresh = 1e2f;
if (beta / BETA_TABLE[n_y_land] > beta_thresh) {
+1 -1
View File
@@ -129,7 +129,7 @@ protected:
virtual bool send() = 0;
/**
* Function to collect/update data for the streams at a high rate independant of
* Function to collect/update data for the streams at a high rate independent of
* actual stream rate.
*
* This function is called at every iteration of the mavlink module.
+1 -1
View File
@@ -167,7 +167,7 @@ parameters:
short: Enable serial flow control for instance ${i}
long: |
This is used to force flow control on or off for the the mavlink
instance. By default it is auto detected. Use when auto detction fails.
instance. By default it is auto detected. Use when auto detection fails.
type: enum
values:
@@ -86,7 +86,7 @@ PARAM_DEFINE_FLOAT(MC_YAW_P, 2.8f);
* in yaw compared to the other axes and it makes sense because yaw is not critical for
* stable hovering or 3D navigation.
*
* For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain.
* For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.
*
* @min 0.0
* @max 1.0
@@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(MC_AT_EN, 0);
* and can be dangerous. Only activate if you know what you
* are doing, and in a safe environment.
*
* Any motion of the remote stick will abord the signal
* Any motion of the remote stick will abort the signal
* injection and reset this parameter
* Best is to perform the identification in position or
* hold mode.
@@ -98,7 +98,7 @@ bool cross_sphere_line(const matrix::Vector3f &sphere_c, const float sphere_r, c
/**
* Adds e.g. feed-forward to the setpoint making sure existing or added NANs have no influence on control.
* This function is udeful to support all the different setpoint combinations of position, velocity, acceleration with NAN representing an uncommited value.
* This function is udeful to support all the different setpoint combinations of position, velocity, acceleration with NAN representing an uncommitted value.
* @param setpoint existing possibly NAN setpoint to add to
* @param addition value/NAN to add to the setpoint
*/
@@ -848,7 +848,7 @@ PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);
PARAM_DEFINE_FLOAT(SYS_VEHICLE_RESP, -0.4f);
/**
* Overall Horizonal Velocity Limit
* Overall Horizontal Velocity Limit
*
* If set to a value greater than zero, other parameters are automatically set (such as
* MPC_XY_VEL_MAX or MPC_VEL_MANUAL).
@@ -359,7 +359,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_EXPO_Y, 0.69f);
* SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO.
*
* 0 Pure Expo function
* 0.7 resonable shape enhancement for intuitive stick feel
* 0.7 reasonable shape enhancement for intuitive stick feel
* 0.95 very strong bent input curve only near maxima have effect
*
* @min 0
@@ -375,7 +375,7 @@ PARAM_DEFINE_FLOAT(MC_ACRO_SUPEXPO, 0.7f);
* SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.
*
* 0 Pure Expo function
* 0.7 resonable shape enhancement for intuitive stick feel
* 0.7 reasonable shape enhancement for intuitive stick feel
* 0.95 very strong bent input curve only near maxima have effect
*
* @min 0
+1 -1
View File
@@ -1858,7 +1858,7 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0);
/**
* Failsafe channel PWM threshold.
*
* Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this theshold.
* Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold.
* By default this is the throttle channel.
*
* Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event,
+1 -1
View File
@@ -100,7 +100,7 @@ PARAM_DEFINE_FLOAT(SENS_FLOW_MAXR, 8.f);
* Optical flow max rate.
*
* Optical flow data maximum publication rate. This is an upper bound,
* actual optical flow data rate is still dependant on the sensor.
* actual optical flow data rate is still dependent on the sensor.
*
* @min 1
* @max 200
+1 -1
View File
@@ -82,7 +82,7 @@ PARAM_DEFINE_INT32(CAL_MAG_ROT_AUTO, 1);
* Magnetometer max rate.
*
* Magnetometer data maximum publication rate. This is an upper bound,
* actual magnetometer data rate is still dependant on the sensor.
* actual magnetometer data rate is still dependent on the sensor.
*
* @min 1
* @max 200
@@ -45,7 +45,7 @@ PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f);
* Baro max rate.
*
* Barometric air data maximum publication rate. This is an upper bound,
* actual barometric data rate is still dependant on the sensor.
* actual barometric data rate is still dependent on the sensor.
*
* @min 1
* @max 200
+1 -1
View File
@@ -562,7 +562,7 @@ void Sih::reconstruct_sensors_signals()
float altitude = (_H0 - _p_I(2)) + _baro_offset_m + generate_wgn() * 0.14f; // altitude with noise
_baro_p_mBar = CONSTANTS_STD_PRESSURE_MBAR * // reconstructed pressure in mBar
powf((1.0f + altitude * TEMP_GRADIENT / T1_K), -CONSTANTS_ONE_G / (TEMP_GRADIENT * CONSTANTS_AIR_GAS_CONST));
_baro_temp_c = T1_K + CONSTANTS_ABSOLUTE_NULL_CELSIUS + TEMP_GRADIENT * altitude; // reconstructed temperture in celcius
_baro_temp_c = T1_K + CONSTANTS_ABSOLUTE_NULL_CELSIUS + TEMP_GRADIENT * altitude; // reconstructed temperture in Celsius
// GPS
_gps_lat_noiseless = _LAT0 + degrees((double)_p_I(0) / CONSTANTS_RADIUS_OF_EARTH);
+3 -3
View File
@@ -159,7 +159,7 @@ private:
// hard constants
static constexpr uint16_t NB_MOTORS = 6;
static constexpr float T1_C = 15.0f; // ground temperature in celcius
static constexpr float T1_C = 15.0f; // ground temperature in Celsius
static constexpr float T1_K = T1_C - CONSTANTS_ABSOLUTE_NULL_CELSIUS; // ground temperature in Kelvin
static constexpr float TEMP_GRADIENT = -6.5f / 1000.0f; // temperature gradient in degrees per metre
// Aerodynamic coefficients
@@ -281,14 +281,14 @@ private:
double _gps_lon, _gps_lon_noiseless;
float _gps_alt, _gps_alt_noiseless;
float _baro_p_mBar; // reconstructed (simulated) pressure in mBar
float _baro_temp_c; // reconstructed (simulated) barometer temperature in celcius
float _baro_temp_c; // reconstructed (simulated) barometer temperature in degrees Celsius
// parameters
float _MASS, _T_MAX, _Q_MAX, _L_ROLL, _L_PITCH, _KDV, _KDW, _H0, _T_TAU;
double _LAT0, _LON0, _COS_LAT0;
matrix::Vector3f _W_I; // weight of the vehicle in inertial frame [N]
matrix::Matrix3f _I; // vehicle inertia matrix
matrix::Matrix3f _Im1; // inverse of the intertia matrix
matrix::Matrix3f _Im1; // inverse of the inertia matrix
matrix::Vector3f _mu_I; // NED magnetic field in inertial frame [G]
int _gps_used;
+9 -9
View File
@@ -55,7 +55,7 @@ PARAM_DEFINE_FLOAT(SIH_MASS, 1.0f);
/**
* Vehicle inertia about X axis
*
* The intertia is a 3 by 3 symmetric matrix.
* The inertia is a 3 by 3 symmetric matrix.
* It represents the difficulty of the vehicle to modify its angular rate.
*
* @unit kg m^2
@@ -69,7 +69,7 @@ PARAM_DEFINE_FLOAT(SIH_IXX, 0.025f);
/**
* Vehicle inertia about Y axis
*
* The intertia is a 3 by 3 symmetric matrix.
* The inertia is a 3 by 3 symmetric matrix.
* It represents the difficulty of the vehicle to modify its angular rate.
*
* @unit kg m^2
@@ -83,7 +83,7 @@ PARAM_DEFINE_FLOAT(SIH_IYY, 0.025f);
/**
* Vehicle inertia about Z axis
*
* The intertia is a 3 by 3 symmetric matrix.
* The inertia is a 3 by 3 symmetric matrix.
* It represents the difficulty of the vehicle to modify its angular rate.
*
* @unit kg m^2
@@ -97,7 +97,7 @@ PARAM_DEFINE_FLOAT(SIH_IZZ, 0.030f);
/**
* Vehicle cross term inertia xy
*
* The intertia is a 3 by 3 symmetric matrix.
* The inertia is a 3 by 3 symmetric matrix.
* This value can be set to 0 for a quad symmetric about its center of mass.
*
* @unit kg m^2
@@ -110,7 +110,7 @@ PARAM_DEFINE_FLOAT(SIH_IXY, 0.0f);
/**
* Vehicle cross term inertia xz
*
* The intertia is a 3 by 3 symmetric matrix.
* The inertia is a 3 by 3 symmetric matrix.
* This value can be set to 0 for a quad symmetric about its center of mass.
*
* @unit kg m^2
@@ -123,7 +123,7 @@ PARAM_DEFINE_FLOAT(SIH_IXZ, 0.0f);
/**
* Vehicle cross term inertia yz
*
* The intertia is a 3 by 3 symmetric matrix.
* The inertia is a 3 by 3 symmetric matrix.
* This value can be set to 0 for a quad symmetric about its center of mass.
*
* @unit kg m^2
@@ -393,7 +393,7 @@ PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Y, 0.0f);
PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Z, 0.0f);
/**
* distance sensor minimun range
* distance sensor minimum range
*
* @unit m
* @min 0.0
@@ -405,7 +405,7 @@ PARAM_DEFINE_FLOAT(SIH_MAG_OFFSET_Z, 0.0f);
PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MIN, 0.0f);
/**
* distance sensor maximun range
* distance sensor maximum range
*
* @unit m
* @min 0.0
@@ -417,7 +417,7 @@ PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MIN, 0.0f);
PARAM_DEFINE_FLOAT(SIH_DISTSNSR_MAX, 100.0f);
/**
* if >= 0 the distance sensor measures will be overrided by this value
* if >= 0 the distance sensor measures will be overridden by this value
*
* Absolute value superior to 10000 will disable distance sensor
*
@@ -39,8 +39,8 @@ equation of the following form:
yi = a0 + a1.xi + a2.xi^2 + a3.xi^3 + .... + an.xi^n + ei , where:
i = [0,m]
xi is the x coordinate (independant variable) of the i'th measurement
yi is the y coordinate (dependant variable) of the i'th measurement
xi is the x coordinate (independent variable) of the i'th measurement
yi is the y coordinate (dependent variable) of the i'th measurement
ei is a random fit error being the difference between the i'th y coordinate
and the value predicted by the polynomial.
@@ -89,8 +89,8 @@ PARAM_DEFINE_FLOAT(VT_B_TRANS_RAMP, 3.0f);
/**
* Output on airbrakes channel during back transition
*
* Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel
* Airbrakes need to be enables for your selected model/mixer
* Used for airbrakes or with ESCs that have reverse thrust enabled on a separate channel.
* Airbrakes need to be enabled for your selected model/mixer.
*
* @min 0
* @max 1