Skip to content

Commit

Permalink
Fix some typos
Browse files Browse the repository at this point in the history
Most are typos, but some words changed to en-GB version.
  • Loading branch information
mishmetall committed Oct 8, 2023
1 parent 65099d0 commit 8597791
Show file tree
Hide file tree
Showing 174 changed files with 287 additions and 287 deletions.
4 changes: 2 additions & 2 deletions AntennaTracker/AntennaTracker.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -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; }

Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_ExternalControl_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down Expand Up @@ -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;
}
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/mode_autorotate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_systemid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand Down
10 changes: 5 additions & 5 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand All @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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) {
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -246,7 +246,7 @@ class Plane : public AP_Vehicle {
#endif

#if HAL_RALLY_ENABLED
// Rally Ponints
// Rally Points
AP_Rally rally;
#endif

Expand Down Expand Up @@ -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;

Expand Down Expand Up @@ -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;

Expand Down Expand Up @@ -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};
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/ekf_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down Expand Up @@ -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) {
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/is_flying.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_acro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_qacro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_qrtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_qstabilize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/motor_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/navigation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)),
Expand Down
Loading

0 comments on commit 8597791

Please sign in to comment.