Copter: Fix typo

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2019-03-25 20:57:55 -03:00 committed by Randy Mackay
parent 55047324ac
commit 33764d6c3b
13 changed files with 14 additions and 14 deletions

View File

@ -4,7 +4,7 @@
// 1. HIL_MODE_SENSORS: full sensor simulation
#define HIL_MODE HIL_MODE_SENSORS
// HIL_PORT SELCTION
// HIL_PORT SELECTION
//
// PORT 1
// If you would like to run telemetry communications for a groundstation

View File

@ -261,7 +261,7 @@ private:
SITL::SITL sitl;
#endif
// Arming/Disarming mangement class
// Arming/Disarming management class
AP_Arming_Copter arming;
// Optical flow sensor

View File

@ -1298,7 +1298,7 @@ bool GCS_MAVLINK_Copter::set_mode(const uint8_t mode)
float GCS_MAVLINK_Copter::vfr_hud_alt() const
{
if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {
// compatability option for older mavlink-aware devices that
// compatibility option for older mavlink-aware devices that
// assume Copter returns a relative altitude in VFR_HUD.alt
return copter.current_loc.alt / 100.0f;
}

View File

@ -1316,7 +1316,7 @@ void Copter::convert_tradheli_parameters(void)
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW_COL_DIR" },
};
// convert single heli paramters without scaling
// convert single heli parameters without scaling
uint8_t table_size = ARRAY_SIZE(singleheli_conversion_info);
for (uint8_t i=0; i<table_size; i++) {
AP_Param::convert_old_parameter(&singleheli_conversion_info[i], 1.0f);

View File

@ -259,7 +259,7 @@ public:
k_param_camera_mount2, // deprecated
//
// Batery monitoring parameters
// Battery monitoring parameters
//
k_param_battery_volt_pin = 168, // deprecated - can be deleted
k_param_battery_curr_pin, // 169 deprecated - can be deleted

View File

@ -2,7 +2,7 @@
#include "RC_Channel.h"
// defining these two macros and including the RC_Channels_VarInfo header defines the parmaeter information common to all vehicle types
// defining these two macros and including the RC_Channels_VarInfo header defines the parameter information common to all vehicle types
#define RC_CHANNELS_SUBCLASS RC_Channels_Copter
#define RC_CHANNEL_SUBCLASS RC_Channel_Copter
@ -136,7 +136,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const control_mode_t mode,
}
}
// do_aux_function - implement the function invoked by auxillary switches
// do_aux_function - implement the function invoked by auxiliary switches
void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
{
switch(ch_option) {

View File

@ -159,7 +159,7 @@
// Radio failsafe
#ifndef FS_RADIO_TIMEOUT_MS
#define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 miliseconds with No RC Input
#define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 milliseconds with No RC Input
#endif
// missing terrain data failsafe

View File

@ -16,7 +16,7 @@
#endif
////////////////////////////////////////////////////////////////////////////////
// EKF_check strucutre
// EKF_check structure
////////////////////////////////////////////////////////////////////////////////
static struct {
uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances

View File

@ -479,7 +479,7 @@ void Copter::Mode::land_run_horizontal_control()
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
// record if pilot has overriden roll or pitch
// record if pilot has overridden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
if (!ap.land_repo_active) {
copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE);

View File

@ -499,7 +499,7 @@ void Copter::ModePosHold::run()
if (!is_zero(target_pitch)) {
// init transition to pilot override
poshold_pitch_controller_to_pilot_override();
// if roll not overriden switch roll-mode to brake (but be ready to go back to loiter any time)
// if roll not overridden switch roll-mode to brake (but be ready to go back to loiter any time)
if (is_zero(target_roll)) {
poshold.roll_mode = POSHOLD_BRAKE_READY_TO_LOITER;
poshold.brake_roll = 0;

View File

@ -285,7 +285,7 @@ void Copter::ModeRTL::descent_run()
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
// record if pilot has overriden roll or pitch
// record if pilot has overridden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
if (!ap.land_repo_active) {
copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE);

View File

@ -82,7 +82,7 @@ void Copter::motor_test_output()
// sanity check throttle values
if (pwm >= MOTOR_TEST_PWM_MIN && pwm <= MOTOR_TEST_PWM_MAX ) {
// 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();

View File

@ -223,7 +223,7 @@ bool Copter::init_arm_motors(const AP_Arming::Method method, const bool do_armin
// log flight mode in case it was changed while vehicle was disarmed
logger.Write_Mode(control_mode, control_mode_reason);
// reenable failsafe
// re-enable failsafe
failsafe_enable();
// perf monitor ignores delay due to arming