|
|
|
@ -36,7 +36,7 @@ static void read_control_switch()
@@ -36,7 +36,7 @@ static void read_control_switch()
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.ch7_option != AUX_SWITCH_SIMPLE_MODE && g.ch8_option != AUX_SWITCH_SIMPLE_MODE && g.ch7_option != AUX_SWITCH_SUPERSIMPLE_MODE && g.ch8_option != AUX_SWITCH_SUPERSIMPLE_MODE) { |
|
|
|
|
if(g.ch7_option != AUXSW_SIMPLE_MODE && g.ch8_option != AUXSW_SIMPLE_MODE && g.ch7_option != AUXSW_SUPERSIMPLE_MODE && g.ch8_option != AUXSW_SUPERSIMPLE_MODE) { |
|
|
|
|
// set Simple mode using stored paramters from Mission planner |
|
|
|
|
// rather than by the control switch |
|
|
|
|
if (BIT_IS_SET(g.super_simple, switch_position)) { |
|
|
|
@ -166,22 +166,22 @@ static void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
@@ -166,22 +166,22 @@ static void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
|
|
|
|
|
{ |
|
|
|
|
// init channel options |
|
|
|
|
switch(ch_option) { |
|
|
|
|
case AUX_SWITCH_SIMPLE_MODE: |
|
|
|
|
case AUX_SWITCH_SONAR: |
|
|
|
|
case AUX_SWITCH_FENCE: |
|
|
|
|
case AUX_SWITCH_RESETTOARMEDYAW: |
|
|
|
|
case AUX_SWITCH_SUPERSIMPLE_MODE: |
|
|
|
|
case AUX_SWITCH_ACRO_TRAINER: |
|
|
|
|
case AUX_SWITCH_EPM: |
|
|
|
|
case AUX_SWITCH_SPRAYER: |
|
|
|
|
case AUX_SWITCH_PARACHUTE_ENABLE: |
|
|
|
|
case AUX_SWITCH_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release |
|
|
|
|
case AUX_SWITCH_RETRACT_MOUNT: |
|
|
|
|
case AUX_SWITCH_MISSIONRESET: |
|
|
|
|
case AUX_SWITCH_ATTCON_FEEDFWD: |
|
|
|
|
case AUX_SWITCH_ATTCON_ACCEL_LIM: |
|
|
|
|
case AUX_SWITCH_RELAY: |
|
|
|
|
case AUX_SWITCH_LANDING_GEAR: |
|
|
|
|
case AUXSW_SIMPLE_MODE: |
|
|
|
|
case AUXSW_SONAR: |
|
|
|
|
case AUXSW_FENCE: |
|
|
|
|
case AUXSW_RESETTOARMEDYAW: |
|
|
|
|
case AUXSW_SUPERSIMPLE_MODE: |
|
|
|
|
case AUXSW_ACRO_TRAINER: |
|
|
|
|
case AUXSW_EPM: |
|
|
|
|
case AUXSW_SPRAYER: |
|
|
|
|
case AUXSW_PARACHUTE_ENABLE: |
|
|
|
|
case AUXSW_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release |
|
|
|
|
case AUXSW_RETRACT_MOUNT: |
|
|
|
|
case AUXSW_MISSION_RESET: |
|
|
|
|
case AUXSW_ATTCON_FEEDFWD: |
|
|
|
|
case AUXSW_ATTCON_ACCEL_LIM: |
|
|
|
|
case AUXSW_RELAY: |
|
|
|
|
case AUXSW_LANDING_GEAR: |
|
|
|
|
do_aux_switch_function(ch_option, ch_flag); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
@ -193,35 +193,35 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -193,35 +193,35 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
int8_t tmp_function = ch_function; |
|
|
|
|
|
|
|
|
|
// multi mode check |
|
|
|
|
if(ch_function == AUX_SWITCH_MULTI_MODE) { |
|
|
|
|
if(ch_function == AUXSW_MULTI_MODE) { |
|
|
|
|
if (g.rc_6.radio_in < CH6_PWM_TRIGGER_LOW) { |
|
|
|
|
tmp_function = AUX_SWITCH_FLIP; |
|
|
|
|
tmp_function = AUXSW_FLIP; |
|
|
|
|
}else if (g.rc_6.radio_in > CH6_PWM_TRIGGER_HIGH) { |
|
|
|
|
tmp_function = AUX_SWITCH_SAVE_WP; |
|
|
|
|
tmp_function = AUXSW_SAVE_WP; |
|
|
|
|
}else{ |
|
|
|
|
tmp_function = AUX_SWITCH_RTL; |
|
|
|
|
tmp_function = AUXSW_RTL; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
switch(tmp_function) { |
|
|
|
|
case AUX_SWITCH_FLIP: |
|
|
|
|
case AUXSW_FLIP: |
|
|
|
|
// flip if switch is on, positive throttle and we're actually flying |
|
|
|
|
if(ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
set_mode(FLIP); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_SIMPLE_MODE: |
|
|
|
|
case AUXSW_SIMPLE_MODE: |
|
|
|
|
// low = simple mode off, middle or high position turns simple mode on |
|
|
|
|
set_simple_mode(ch_flag == AUX_SWITCH_HIGH || ch_flag == AUX_SWITCH_MIDDLE); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_SUPERSIMPLE_MODE: |
|
|
|
|
case AUXSW_SUPERSIMPLE_MODE: |
|
|
|
|
// low = simple mode off, middle = simple mode, high = super simple mode |
|
|
|
|
set_simple_mode(ch_flag); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_RTL: |
|
|
|
|
case AUXSW_RTL: |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
// engage RTL (if not possible we remain in current flight mode) |
|
|
|
|
set_mode(RTL); |
|
|
|
@ -233,13 +233,13 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -233,13 +233,13 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_SAVE_TRIM: |
|
|
|
|
case AUXSW_SAVE_TRIM: |
|
|
|
|
if ((ch_flag == AUX_SWITCH_HIGH) && (control_mode <= ACRO) && (g.rc_3.control_in == 0)) { |
|
|
|
|
save_trim(); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_SAVE_WP: |
|
|
|
|
case AUXSW_SAVE_WP: |
|
|
|
|
// save waypoint when switch is brought high |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
|
|
|
|
@ -294,14 +294,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -294,14 +294,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
case AUX_SWITCH_CAMERA_TRIGGER: |
|
|
|
|
case AUXSW_CAMERA_TRIGGER: |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
do_take_picture(); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_SONAR: |
|
|
|
|
case AUXSW_SONAR: |
|
|
|
|
// enable or disable the sonar |
|
|
|
|
#if CONFIG_SONAR == ENABLED |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
@ -313,7 +313,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -313,7 +313,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if AC_FENCE == ENABLED |
|
|
|
|
case AUX_SWITCH_FENCE: |
|
|
|
|
case AUXSW_FENCE: |
|
|
|
|
// enable or disable the fence |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
fence.enable(true); |
|
|
|
@ -325,7 +325,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -325,7 +325,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
// To-Do: add back support for this feature |
|
|
|
|
//case AUX_SWITCH_RESETTOARMEDYAW: |
|
|
|
|
//case AUXSW_RESETTOARMEDYAW: |
|
|
|
|
// if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
// set_yaw_mode(YAW_RESETTOARMEDYAW); |
|
|
|
|
// }else{ |
|
|
|
@ -333,7 +333,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -333,7 +333,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
// } |
|
|
|
|
// break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_ACRO_TRAINER: |
|
|
|
|
case AUXSW_ACRO_TRAINER: |
|
|
|
|
switch(ch_flag) { |
|
|
|
|
case AUX_SWITCH_LOW: |
|
|
|
|
g.acro_trainer = ACRO_TRAINER_DISABLED; |
|
|
|
@ -350,7 +350,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -350,7 +350,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
#if EPM_ENABLED == ENABLED |
|
|
|
|
case AUX_SWITCH_EPM: |
|
|
|
|
case AUXSW_EPM: |
|
|
|
|
switch(ch_flag) { |
|
|
|
|
case AUX_SWITCH_LOW: |
|
|
|
|
epm.release(); |
|
|
|
@ -364,14 +364,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -364,14 +364,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
#if SPRAYER == ENABLED |
|
|
|
|
case AUX_SWITCH_SPRAYER: |
|
|
|
|
case AUXSW_SPRAYER: |
|
|
|
|
sprayer.enable(ch_flag == AUX_SWITCH_HIGH); |
|
|
|
|
// if we are disarmed the pilot must want to test the pump |
|
|
|
|
sprayer.test_pump((ch_flag == AUX_SWITCH_HIGH) && !motors.armed()); |
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_AUTO: |
|
|
|
|
case AUXSW_AUTO: |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
set_mode(AUTO); |
|
|
|
|
}else{ |
|
|
|
@ -383,7 +383,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -383,7 +383,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if AUTOTUNE_ENABLED == ENABLED |
|
|
|
|
case AUX_SWITCH_AUTOTUNE: |
|
|
|
|
case AUXSW_AUTOTUNE: |
|
|
|
|
// turn on auto tuner |
|
|
|
|
switch(ch_flag) { |
|
|
|
|
case AUX_SWITCH_LOW: |
|
|
|
@ -401,7 +401,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -401,7 +401,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_LAND: |
|
|
|
|
case AUXSW_LAND: |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
set_mode(LAND); |
|
|
|
|
}else{ |
|
|
|
@ -413,18 +413,18 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -413,18 +413,18 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if PARACHUTE == ENABLED |
|
|
|
|
case AUX_SWITCH_PARACHUTE_ENABLE: |
|
|
|
|
case AUXSW_PARACHUTE_ENABLE: |
|
|
|
|
// Parachute enable/disable |
|
|
|
|
parachute.enabled(ch_flag == AUX_SWITCH_HIGH); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_PARACHUTE_RELEASE: |
|
|
|
|
case AUXSW_PARACHUTE_RELEASE: |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
parachute_manual_release(); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_PARACHUTE_3POS: |
|
|
|
|
case AUXSW_PARACHUTE_3POS: |
|
|
|
|
// Parachute disable, enable, release with 3 position switch |
|
|
|
|
switch (ch_flag) { |
|
|
|
|
case AUX_SWITCH_LOW: |
|
|
|
@ -443,24 +443,24 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -443,24 +443,24 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_MISSIONRESET: |
|
|
|
|
case AUXSW_MISSION_RESET: |
|
|
|
|
if (ch_flag == AUX_SWITCH_HIGH) { |
|
|
|
|
mission.reset(); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_ATTCON_FEEDFWD: |
|
|
|
|
case AUXSW_ATTCON_FEEDFWD: |
|
|
|
|
// enable or disable feed forward |
|
|
|
|
attitude_control.bf_feedforward(ch_flag == AUX_SWITCH_HIGH); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_ATTCON_ACCEL_LIM: |
|
|
|
|
case AUXSW_ATTCON_ACCEL_LIM: |
|
|
|
|
// enable or disable accel limiting by restoring defaults |
|
|
|
|
attitude_control.accel_limiting(ch_flag == AUX_SWITCH_HIGH); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if MOUNT == ENABLE |
|
|
|
|
case AUX_SWITCH_RETRACT_MOUNT: |
|
|
|
|
case AUXSW_RETRACT_MOUNT: |
|
|
|
|
switch (ch_flag) { |
|
|
|
|
case AUX_SWITCH_HIGH: |
|
|
|
|
camera_mount.set_mode(MAV_MOUNT_MODE_RETRACT); |
|
|
|
@ -472,11 +472,11 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
@@ -472,11 +472,11 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_RELAY: |
|
|
|
|
case AUXSW_RELAY: |
|
|
|
|
ServoRelayEvents.do_set_relay(0, ch_flag == AUX_SWITCH_HIGH); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUX_SWITCH_LANDING_GEAR: |
|
|
|
|
case AUXSW_LANDING_GEAR: |
|
|
|
|
switch (ch_flag) { |
|
|
|
|
case AUX_SWITCH_LOW: |
|
|
|
|
landinggear.set_cmd_mode(LandingGear_Deploy); |
|
|
|
|