mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Motors: Fix typos
This commit is contained in:
parent
dfe38b61de
commit
2802775e7d
@ -52,7 +52,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
|
||||
|
||||
// @Param: COL_MID
|
||||
// @DisplayName: Collective Pitch Mid-Point
|
||||
// @Description: Swash servo position corresponding to zero collective pitch (or zero lift for Assymetrical blades)
|
||||
// @Description: Swash servo position corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
|
||||
// @Range: 1000 2000
|
||||
// @Units: PWM
|
||||
// @Increment: 1
|
||||
|
@ -186,7 +186,7 @@ protected:
|
||||
AP_Int16 _cyclic_max; // Maximum cyclic angle of the swash plate in centi-degrees
|
||||
AP_Int16 _collective_min; // Lowest possible servo position for the swashplate
|
||||
AP_Int16 _collective_max; // Highest possible servo position for the swashplate
|
||||
AP_Int16 _collective_mid; // Swash servo position corresponding to zero collective pitch (or zero lift for Assymetrical blades)
|
||||
AP_Int16 _collective_mid; // Swash servo position corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
|
||||
AP_Int8 _servo_mode; // Pass radio inputs directly to servos during set-up through mission planner
|
||||
AP_Int16 _rsc_setpoint; // rotor speed when RSC mode is set to is enabledv
|
||||
AP_Int8 _rsc_mode; // Which main rotor ESC control mode is active
|
||||
|
@ -300,7 +300,7 @@ void AP_MotorsHeli_Single::calculate_roll_pitch_collective_factors()
|
||||
_collectiveFactor[CH_2] = 1;
|
||||
_collectiveFactor[CH_3] = 1;
|
||||
|
||||
}else{ //H1 Swashplate, keep servo outputs seperated
|
||||
}else{ //H1 Swashplate, keep servo outputs separated
|
||||
|
||||
// roll factors
|
||||
_rollFactor[CH_1] = 1;
|
||||
|
Loading…
Reference in New Issue
Block a user