From b7c040e8bc1d5598f2aae23c408229f7cd019dd1 Mon Sep 17 00:00:00 2001 From: Mykhailo Kuznietsov Date: Wed, 11 Oct 2023 18:41:54 +1100 Subject: [PATCH] ArduPlane: Fix some typos Fixed some typos found in the code. --- 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 +++--- 20 files changed, 40 insertions(+), 40 deletions(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 9bba585d0f..39a9461ea6 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 b0cddc9081..720eed4c27 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 e9c25ea5da..7210bfe777 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -421,7 +421,7 @@ public: 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 @@ public: 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 9634184c83..fe8a935dc7 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -246,7 +246,7 @@ private: #endif #if HAL_RALLY_ENABLED - // Rally Ponints + // Rally Points AP_Rally rally; #endif @@ -312,7 +312,7 @@ private: // 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 @@ private: // 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 @@ private: 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 bf2b930009..aea5447a21 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 86b972225c..e36e4ef1ab 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 122b3dc361..f49814aca9 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 3b2c27396f..ffe578736a 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 acf0f49752..c15970b9bd 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 b74a434384..d49e1e0fb6 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 e31e4681ad..9be1c962bd 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 659d674736..2f78a210fb 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 67dee708b5..38229d2f35 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 b60b442646..76846b0fe6 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 93d062d38d..9557637af4 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 ae6f3c69c5..ced4252578 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 6f21b75abc..7c7066bef0 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 ffc8c76c25..f40fa33d1f 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 73290a5f06..5574ad2c9b 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 8f5c37f5d5..e8babe5e86 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 {