ArduCopter: Fix some typos

Fixed some typos found in the code.
This commit is contained in:
Mykhailo Kuznietsov 2023-10-11 18:41:54 +11:00 committed by Peter Barker
parent f659b7bfee
commit 3a231f8b32
4 changed files with 6 additions and 6 deletions

View File

@ -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,

View File

@ -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;
}

View File

@ -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

View File

@ -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);
}