diff --git a/ArduCopter/APM_Config_mavlink_hil.h b/ArduCopter/APM_Config_mavlink_hil.h index dad432892d..9c5d37c78a 100644 --- a/ArduCopter/APM_Config_mavlink_hil.h +++ b/ArduCopter/APM_Config_mavlink_hil.h @@ -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 diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 5cd234b26d..ce1c67a2c7 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -261,7 +261,7 @@ private: SITL::SITL sitl; #endif - // Arming/Disarming mangement class + // Arming/Disarming management class AP_Arming_Copter arming; // Optical flow sensor diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index dfbcd9e149..3b4848e927 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -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; } diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 79d381ed31..c10a22c449 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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; iget_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); diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index ee24324347..927e1e4797 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -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; diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 4b0fcfc244..7e6e8a479c 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -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); diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 18e2ef463b..a0138a0e18 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -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(); diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index cdf69a6b5d..03403b4bbc 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -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