Browse Source

Copter: ch7/8 switch for auto pause/continue

- added new mode for CH7/CH8 (#24, auto mission reset)
- changed mission.start() to mission.start_or_resume() in auto_init()
master
Andrew Chapman 11 years ago committed by Randy Mackay
parent
commit
3f0a52cb53
  1. 4
      ArduCopter/Parameters.pde
  2. 4
      ArduCopter/control_auto.pde
  3. 10
      ArduCopter/control_modes.pde
  4. 1
      ArduCopter/defines.h
  5. 5
      ArduCopter/flight_mode.pde

4
ArduCopter/Parameters.pde

@ -384,14 +384,14 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -384,14 +384,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: CH7_OPT
// @DisplayName: Channel 7 option
// @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:Sonar, 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
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 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
// @User: Standard
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
// @Param: CH8_OPT
// @DisplayName: Channel 8 option
// @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:Sonar, 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
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 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
// @User: Standard
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),

4
ArduCopter/control_auto.pde

@ -30,8 +30,8 @@ static bool auto_init(bool ignore_checks) @@ -30,8 +30,8 @@ static bool auto_init(bool ignore_checks)
// initialise waypoint and spline controller
wp_nav.wp_and_spline_init();
// start the mission
mission.start();
// start/resume the mission (based on MIS_AUTORESET param)
mission.start_or_resume();
return true;
}else{
return false;

10
ArduCopter/control_modes.pde

@ -112,9 +112,11 @@ static void init_aux_switches() @@ -112,9 +112,11 @@ static void init_aux_switches()
case AUX_SWITCH_EKF:
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_MISSIONRESET:
do_aux_switch_function(g.ch7_option, ap.CH7_flag);
break;
}
// init channel 8 option
switch(g.ch8_option) {
case AUX_SWITCH_SIMPLE_MODE:
@ -128,6 +130,7 @@ static void init_aux_switches() @@ -128,6 +130,7 @@ static void init_aux_switches()
case AUX_SWITCH_EKF:
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_MISSIONRESET:
do_aux_switch_function(g.ch8_option, ap.CH8_flag);
break;
}
@ -398,7 +401,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) @@ -398,7 +401,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
parachute_manual_release();
break;
}
break;
#endif
case AUX_SWITCH_MISSIONRESET:
if (ch_flag == AUX_SWITCH_HIGH) {
mission.reset();
}
break;
}
}

1
ArduCopter/defines.h

@ -56,6 +56,7 @@ @@ -56,6 +56,7 @@
#define AUX_SWITCH_PARACHUTE_ENABLE 21 // Parachute enable/disable
#define AUX_SWITCH_PARACHUTE_RELEASE 22 // Parachute release
#define AUX_SWITCH_PARACHUTE_3POS 23 // Parachute disable, enable, release with 3 position switch
#define AUX_SWITCH_MISSIONRESET 24 // Reset auto mission to start from first command
// 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)

5
ArduCopter/flight_mode.pde

@ -208,6 +208,11 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) @@ -208,6 +208,11 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
}
#endif
// stop mission when we leave auto mode
if (old_control_mode == AUTO) {
mission.stop();
}
// smooth throttle transition when switching from manual to automatic flight modes
if (manual_flight_mode(old_control_mode) && !manual_flight_mode(new_control_mode) && motors.armed() && !ap.land_complete) {
// this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle

Loading…
Cancel
Save