Copter: move relay from ch6 to ch7/ch8

This commit is contained in:
Randy Mackay 2014-08-09 13:36:35 +09:00
parent 3ee3a71644
commit 0518439841
4 changed files with 11 additions and 9 deletions

View File

@ -1510,11 +1510,6 @@ static void tuning(){
g.acro_yaw_p = tuning_value; g.acro_yaw_p = tuning_value;
break; break;
case CH6_RELAY:
if (g.rc_6.control_in > 525) relay.on(0);
if (g.rc_6.control_in < 475) relay.off(0);
break;
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
case CH6_HELI_EXTERNAL_GYRO: case CH6_HELI_EXTERNAL_GYRO:
motors.ext_gyro_gain(g.rc_6.control_in); motors.ext_gyro_gain(g.rc_6.control_in);

View File

@ -361,7 +361,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Channel 6 Tuning // @DisplayName: Channel 6 Tuning
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob // @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
// @User: Standard // @User: Standard
// @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,14:Altitude Hold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,42:Loiter Speed,12:Loiter Pos kP,22:Loiter Rate kP,28:Loiter Rate kI,23:Loiter Rate kD,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,9:Relay On/Off,13:Heli Ext Gyro,17:OF Loiter kP,18:OF Loiter kI,19:OF Loiter kD,30:AHRS Yaw kP,31:AHRS kP,38:Declination,39:Circle Rate,41:RangeFinder Gain,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF // @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,14:Altitude Hold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,42:Loiter Speed,12:Loiter Pos kP,22:Loiter Rate kP,28:Loiter Rate kI,23:Loiter Rate kD,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,13:Heli Ext Gyro,17:OF Loiter kP,18:OF Loiter kI,19:OF Loiter kD,30:AHRS Yaw kP,31:AHRS kP,38:Declination,39:Circle Rate,41:RangeFinder Gain,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF
GSCALAR(radio_tuning, "TUNE", 0), GSCALAR(radio_tuning, "TUNE", 0),
// @Param: TUNE_LOW // @Param: TUNE_LOW
@ -388,14 +388,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: CH7_OPT // @Param: CH7_OPT
// @DisplayName: Channel 7 option // @DisplayName: Channel 7 option
// @Description: Select which function if performed when CH7 is above 1800 pwm // @Description: Select which function if performed when CH7 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off
// @User: Standard // @User: Standard
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION), GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
// @Param: CH8_OPT // @Param: CH8_OPT
// @DisplayName: Channel 8 option // @DisplayName: Channel 8 option
// @Description: Select which function if performed when CH8 is above 1800 pwm // @Description: Select which function if performed when CH8 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off
// @User: Standard // @User: Standard
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION), GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),

View File

@ -56,6 +56,7 @@
#define AUX_SWITCH_ATTCON_FEEDFWD 25 // enable/disable the roll and pitch rate feed forward #define AUX_SWITCH_ATTCON_FEEDFWD 25 // enable/disable the roll and pitch rate feed forward
#define AUX_SWITCH_ATTCON_ACCEL_LIM 26 // enable/disable the roll, pitch and yaw accel limiting #define AUX_SWITCH_ATTCON_ACCEL_LIM 26 // enable/disable the roll, pitch and yaw accel limiting
#define AUX_SWITCH_RETRACT_MOUNT 27 // Retract Mount #define AUX_SWITCH_RETRACT_MOUNT 27 // Retract Mount
#define AUX_SWITCH_RELAY 28 // Relay pin on/off (only supports first relay)
// values used by the ap.ch7_opt and ap.ch8_opt flags // values used by the ap.ch7_opt and ap.ch8_opt flags
#define AUX_SWITCH_LOW 0 // indicates auxiliar switch is in the low position (pwm <1200) #define AUX_SWITCH_LOW 0 // indicates auxiliar switch is in the low position (pwm <1200)
@ -126,7 +127,7 @@
#define CH6_WP_SPEED 10 // maximum speed to next way point (0 to 10m/s) #define CH6_WP_SPEED 10 // maximum speed to next way point (0 to 10m/s)
#define CH6_ACRO_RP_KP 25 // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate #define CH6_ACRO_RP_KP 25 // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
#define CH6_ACRO_YAW_KP 40 // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate #define CH6_ACRO_YAW_KP 40 // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
#define CH6_RELAY 9 // switch relay on if ch6 high, off if low #define CH6_RELAY 9 // deprecated -- remove
#define CH6_HELI_EXTERNAL_GYRO 13 // TradHeli specific external tail gyro gain #define CH6_HELI_EXTERNAL_GYRO 13 // TradHeli specific external tail gyro gain
#define CH6_OPTFLOW_KP 17 // optical flow loiter controller's P term (position error to tilt angle) #define CH6_OPTFLOW_KP 17 // optical flow loiter controller's P term (position error to tilt angle)
#define CH6_OPTFLOW_KI 18 // optical flow loiter controller's I term (position error to tilt angle) #define CH6_OPTFLOW_KI 18 // optical flow loiter controller's I term (position error to tilt angle)

View File

@ -116,6 +116,7 @@ static void init_aux_switches()
case AUX_SWITCH_MISSIONRESET: case AUX_SWITCH_MISSIONRESET:
case AUX_SWITCH_ATTCON_FEEDFWD: case AUX_SWITCH_ATTCON_FEEDFWD:
case AUX_SWITCH_ATTCON_ACCEL_LIM: case AUX_SWITCH_ATTCON_ACCEL_LIM:
case AUX_SWITCH_RELAY:
do_aux_switch_function(g.ch7_option, ap.CH7_flag); do_aux_switch_function(g.ch7_option, ap.CH7_flag);
break; break;
} }
@ -137,6 +138,7 @@ static void init_aux_switches()
case AUX_SWITCH_MISSIONRESET: case AUX_SWITCH_MISSIONRESET:
case AUX_SWITCH_ATTCON_FEEDFWD: case AUX_SWITCH_ATTCON_FEEDFWD:
case AUX_SWITCH_ATTCON_ACCEL_LIM: case AUX_SWITCH_ATTCON_ACCEL_LIM:
case AUX_SWITCH_RELAY:
do_aux_switch_function(g.ch8_option, ap.CH8_flag); do_aux_switch_function(g.ch8_option, ap.CH8_flag);
break; break;
} }
@ -440,6 +442,10 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
} }
break; break;
#endif #endif
case AUX_SWITCH_RELAY:
ServoRelayEvents.do_set_relay(0, ch_flag == AUX_SWITCH_HIGH);
break;
} }
} }