Rewrote tail and main rotor ramp up methods
Moved direct drive ESC speed control into rsc_control method
Pass in ch7 servo as servo_aux to TradHeli motors object constructor
split CH7_SETPOINT parameter into GYR_GAIN and DIRECTDRIVE parameters
replaced RSC_RATE with uint8_t RSC_RAMP_TIME parameter
rename GOV_SETPOINT parameter to RSC_SETPOINT
RSC_MODE parameter description updated to indicate it controls the
source of main rotor speed
#define AP_MOTORS_HELI_RSC_MODE_NONE 0 // main rotor ESC is directly connected to receiver
#define AP_MOTORS_HELI_RSC_MODE_NONE 0 // main rotor ESC is directly connected to receiver, pilot controls ESC speed through transmitter directly
#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_CH8_PASSTHROUGH 1 // main rotor ESC is connected to RC8 (out), pilot desired rotor speed provided by CH8 input
#define AP_MOTORS_HELI_RSC_MODE_EXT_GOVERNOR 2 // main rotor ESC is connected to RC8 and controlled by arducopter
#define AP_MOTORS_HELI_RSC_MODE_SETPOINT 2 // main rotor ESC is connected to RC8 (out), desired speed is held in RSC_SETPOINT parameter
// default main rotor governor set-point (ch8 out)
// default main rotor speed (ch8 out) as a number from 0 ~ 1000
#define AP_MOTORS_HELI_EXT_GOVERNOR_SETPOINT 1500
#define AP_MOTORS_HELI_RSC_SETPOINT 500
// default main rotor ramp up time in seconds
#define AP_MOTORS_HELI_RSC_RAMP_TIME 1 // 1 seconds (most people use exterrnal govenors so we can ramp up output to rotor quickly)
#define AP_MOTORS_HELI_TAIL_RAMP_INCREMENT 5 // 5 is 2 seconds for direct drive tail rotor to reach to full speed (5 = (2sec*100hz)/1000)
// default main rotor ramp up rate in 100th of seconds
// has_flybar - returns true if we have a mechical flybar
// has_flybar - returns true if we have a mechical flybar
boolhas_flybar(){return_flybar_mode;}
boolhas_flybar(){return_flybar_mode;}
@ -174,6 +178,9 @@ public:
// return true if the main rotor is up to speed
// return true if the main rotor is up to speed
boolmotor_runup_complete();
boolmotor_runup_complete();
// recalc_scalers - recalculates various scalers used. Should be called at about 1hz to allow users to see effect of changing parameters
voidrecalc_scalers();
// var_info for holding Parameter information
// var_info for holding Parameter information
staticconststructAP_Param::GroupInfovar_info[];
staticconststructAP_Param::GroupInfovar_info[];
@ -197,15 +204,32 @@ private:
// calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
// calculate_roll_pitch_collective_factors - calculate factors based on swash type and servo position
voidcalculate_roll_pitch_collective_factors();
voidcalculate_roll_pitch_collective_factors();
// rsc_control - update value to send to main rotor's ESC
// rsc_control - main function to update values to send to main rotor and tail rotor ESCs
voidrsc_control();
voidrsc_control(int16_tdesired_rotor_speed);
// rotor_ramp - ramps rotor towards target. result put rotor_out and sent to ESC
voidrotor_ramp(int16_trotor_target);
// tail_ramp - ramps tail motor towards target. Only used for direct drive variable pitch tails
// results put into _tail_direct_drive_out and sent to ESC
voidtail_ramp(int16_ttail_target);
// return true if the tail rotor is up to speed
booltail_rotor_runup_complete();
// write_rsc - outputs pwm onto output rsc channel (ch8). servo_out parameter is of the range 0 ~ 1000
voidwrite_rsc(int16_tservo_out);
// write_aux - outputs pwm onto output aux channel (ch7). servo_out parameter is of the range 0 ~ 1000
voidwrite_aux(int16_tservo_out);
// external objects we depend upon
// external objects we depend upon
RC_Channel*_servo_1;
RC_Channel*_servo_aux;// output to ext gyro gain and tail direct drive esc (ch7)
RC_Channel*_servo_2;
RC_Channel*_servo_rsc;// output to main rotor esc (ch8)
RC_Channel*_servo_3;
RC_Channel*_servo_1;// swash plate servo #1
RC_Channel*_servo_4;
RC_Channel*_servo_2;// swash plate servo #2
RC_Channel*_rc_8;
RC_Channel*_servo_3;// swash plate servo #3
RC_Channel*_servo_4;// tail servo
// flags bitmask
// flags bitmask
structheliflags_type{
structheliflags_type{
@ -225,17 +249,18 @@ private:
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 Assymetrical blades)
AP_Int16_tail_type;// Tail type used: Servo, Servo with external gyro, direct drive variable pitch or direct drive fixed pitch
AP_Int16_tail_type;// Tail type used: Servo, Servo with external gyro, direct drive variable pitch or direct drive fixed pitch
AP_Int8_swash_type;// Swash Type Setting - either 3-servo CCPM or H1 Mechanical Mixing
AP_Int8_swash_type;// Swash Type Setting - either 3-servo CCPM or H1 Mechanical Mixing
AP_Int16_ch7_pwm_setpoint;// PWM sent to Ch7 for ext gyro gain or direct drive variable pitch motor
AP_Int16_ext_gyro_gain;// PWM sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
AP_Int8_servo_manual;// Pass radio inputs directly to servos during set-up through mission planner
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_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_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_Int16_rsc_setpoint;// rotor speed when RSC mode is set to is enabledv
AP_Int8_rsc_mode;// Sets which main rotor ESC control mode is active
AP_Int8_rsc_mode;// 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_rsc_ramp_time;// Time in seconds to ramp up the main rotor to full speed
AP_Int8_flybar_mode;// Flybar present or not. Affects attitude controller used during ACRO flight mode
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_min;// Minimum collective position while pilot directly controls the collective
AP_Int8_manual_collective_max;// Maximum collective position while pilot directly controls the collective
AP_Int8_manual_collective_max;// Maximum collective position while pilot directly controls the collective
AP_Int16_land_collective_min;// Minimum collective when landed or landing
AP_Int16_land_collective_min;// Minimum collective when landed or landing
AP_Int16_direct_drive_tailspeed;// Direct Drive VarPitch Tail ESC speed (0 ~ 1000)
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)
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_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_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
float_rotor_out;// output to the rotor (0 ~ 1000)
int16_t_rsc_ramp;// current state of ramping
float_rsc_ramp_increment;// the amount we can increase the rotor output during each 100hz iteration
int16_t_motor_runup_timer;// timer to determine if motor has run up fully
int16_t_tail_direct_drive_out;// current ramped speed of output on ch7 when using direct drive variable pitch tail type