#define AP_MOTORS_HELI_RSC_MODE_NONE 0 // main rotor ESC is directly connected to receiver
#define AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH 1 // main rotor ESC is connected to RC8 (out) but pilot still directly controls speed with a passthrough from CH8 (in)
#define AP_MOTORS_HELI_RSC_MODE_EXT_GOVERNOR 2 // main rotor ESC is connected to RC8 and controlled by arducopter
uint8_tswash_initialised:1;// true if swash has been initialised
uint8_tlanding_collective:1;// true if collective is setup for landing which has much higher minimum
uint8_tmotor_runup_complete:1;// true if the rotors have had enough time to wind up
}_heliflags;
// parameters
AP_Int16_servo1_pos;// Angular location of swash servo #1
AP_Int16_servo2_pos;// Angular location of swash servo #2
AP_Int16_servo3_pos;// Angular location of swash servo #3
AP_Int16_roll_max;// Maximum roll angle of the swash plate in centi-degrees
AP_Int16_pitch_max;// Maximum pitch 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_ext_gyro_enabled;// Enabled/Disable an external rudder gyro connected to channel 7. With no external gyro a more complex yaw controller is used
AP_Int8_swash_type;// Swash Type Setting - either 3-servo CCPM or H1 Mechanical Mixing
AP_Int16_ext_gyro_gain;// PWM sent to the external gyro on Ch7
AP_Int8_servo_manual;// Pass radio inputs directly to servos during set-up through mission planner
AP_Int16_phase_angle;// Phase angle correction for rotor head. If pitching the swash forward induces a roll, this can be correct the problem
AP_Int16_collective_yaw_effect;// Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
AP_Int16_ext_gov_setpoint;// PWM passed to the external motor governor when external governor is enabledv
AP_Int8_rsc_mode;// Sets which main rotor ESC control mode is active
AP_Int16_rsc_ramp_up_rate;// The time in 100th seconds the RSC takes to ramp up to speed
AP_Int8_flybar_mode;// Flybar present or not. Affects attitude controller used during ACRO flight mode
AP_Int8_manual_collective_min;// Minimum collective position while pilot directly controls the collective
AP_Int8_manual_collective_max;// Maximum collective position while pilot directly controls the collective
float_roll_scaler;// scaler to convert roll input from radio (i.e. -4500 ~ 4500) to max roll range
float_pitch_scaler;// scaler to convert pitch input from radio (i.e. -4500 ~ 4500) to max pitch range
float_collective_scalar;// collective scalar to convert pwm form (i.e. 0 ~ 1000) passed in to actual servo range (i.e 1250~1750 would be 500)
float_collective_scalar_manual;// collective scalar to reduce the range of the collective movement while collective is being controlled manually (i.e. directly by the pilot)
int16_t_collective_out;// actual collective pitch value. Required by the main code for calculating cruise throttle
int16_t_collective_mid_pwm;// collective mid parameter value converted to pwm form (i.e. 0 ~ 1000)
int16_t_rsc_output;// final output to the external motor governor 1000-2000
int16_t_rsc_ramp;// current state of ramping
int16_t_motor_runup_timer;// timer to determine if motor has run up fully