// @Description: Setting this to Enabled(1) will enable an external rudder gyro control which means outputting a gain on channel 7 and using a simpler heading control algorithm. Setting this to Disabled(0) will disable the external gyro gain on channel 7 and revert to a more complex yaw control algorithm.
// @Description: Enabled/Disable an external rudder gyro connected to channel 7. With no external gyro a more complex yaw controller is used
// @Description: Setting this to Enabled(1) will pass radio inputs directly to servos. Setting this to Disabled(0) will enable Arducopter control of servos. This is only meant to be used by the Mission Planner using swash plate set-up.
// @Description: Pass radio inputs directly to servos for set-up. Do not set this manually!
// @Description: This corrects for phase angle errors of the helicopter main rotor head. For example if pitching the swash forward also induces a roll, that effect can be offset with this parameter.
// @Description: Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
// @Description: This is a feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
// @Description: Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
@ -545,7 +546,7 @@ static long map(long x, long in_min, long in_max, long out_min, long out_max)
@@ -545,7 +546,7 @@ static long map(long x, long in_min, long in_max, long out_min, long out_max)
voidAP_MotorsHeli::rsc_control(){
if(armed()&&(rsc_ramp>=rsc_ramp_up_rate)){// rsc_ramp will never increase if rsc_mode = 0
if(motor_runup_timer<MOTOR_RUNUP_TIME){// therefore motor_runup_complete can never be true
if(motor_runup_timer<AP_MOTORS_HELI_MOTOR_RUNUP_TIME){// therefore motor_runup_complete can never be true
AP_Int8servo_manual;// used to trigger swash reset from mission planner
AP_Int16ext_gov_setpoint;// maximum output to the motor governor
AP_Int8rsc_mode;// sets the mode for rotor speed controller
AP_Int16rsc_ramp_up_rate;// sets the time in 100th seconds the RSC takes to ramp up to speed
AP_Int8flybar_mode;// selects FBL Acro Mode, or Flybarred Acro Mode
RC_Channel*_servo_4;
RC_Channel*_rc_8;
// parameters
AP_Int16servo1_pos;// Angular location of swash servo #1
AP_Int16servo2_pos;// Angular location of swash servo #2
AP_Int16servo3_pos;// Angular location of swash servo #3
AP_Int16roll_max;// Maximum roll angle of the swash plate in centi-degrees
AP_Int16pitch_max;// Maximum pitch angle of the swash plate in centi-degrees
AP_Int16collective_min;// Lowest possible servo position for the swashplate
AP_Int16collective_max;// Highest possible servo position for the swashplate
AP_Int16collective_mid;// Swash servo position corresponding to zero collective pitch (or zero lift for Assymetrical blades)
AP_Int16ext_gyro_enabled;// Enabled/Disable an external rudder gyro connected to channel 7. With no external gyro a more complex yaw controller is used
AP_Int8swash_type;// Swash Type Setting - either 3-servo CCPM or H1 Mechanical Mixing
AP_Int16ext_gyro_gain;// PWM sent to the external gyro on Ch7
AP_Int8servo_manual;// Pass radio inputs directly to servos during set-up through mission planner
AP_Int16phase_angle;// Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
AP_Int16collective_yaw_effect;// Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
AP_Int16ext_gov_setpoint;// PWM passed to the external motor governor when external governor is enabledv
AP_Int8rsc_mode;// Sets which main rotor ESC control mode is active
AP_Int16rsc_ramp_up_rate;// The time in 100th seconds the RSC takes to ramp up to speed
AP_Int8flybar_mode;// Flybar present or not. Affects attitude controller used during ACRO flight mode
AP_Int8stab_col_min;// Minimum collective position while flying in Stabilize Mode
AP_Int8stab_col_max;// Maximum collective position while flying in Stabilize Mode
// internal variables
int16_tthrottle_mid;// throttle mid point in pwm form (i.e. 0 ~ 1000)
AP_Int8stab_col_min;// collective pitch minimum in Stabilize Mode
AP_Int8stab_col_max;// collective pitch maximum in Stabilize Mode
boolstab_throttle;// true if we are in Stabilize Mode for reduced Swash Range
boolstab_throttle;// true if we are in Stabilize Mode for reduced Swash Range
boolmotor_runup_complete;// true if the rotors have had enough time to wind up
int16_tcoll_out;// returns the actual collective in use to the main code
int16_tcoll_out;// returns the actual collective in use to the main code