diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde
index 41cdcfb0422ddeff128101650b0b0f16ae83b5e2..ceac84bcd94c3b1e44099a1b7981baee76c2081a 100644
--- a/ArduCopter/control_modes.pde
+++ b/ArduCopter/control_modes.pde
@@ -110,6 +110,8 @@ static void init_aux_switches()
         case AUX_SWITCH_EPM:
         case AUX_SWITCH_SPRAYER:
         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
             do_aux_switch_function(g.ch7_option, ap.CH7_flag);
             break;
     }
@@ -124,6 +126,8 @@ static void init_aux_switches()
         case AUX_SWITCH_EPM:
         case AUX_SWITCH_SPRAYER:
         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
             do_aux_switch_function(g.ch8_option, ap.CH8_flag);
             break;
     }
@@ -365,7 +369,34 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
         ahrs.set_ekf_use(ch_flag==AUX_SWITCH_HIGH);
         break;
 #endif
-        
+
+#if PARACHUTE == ENABLED
+    case AUX_SWITCH_PARACHUTE_ENABLE:
+        // Parachute enable/disable
+        parachute.enabled(ch_flag == AUX_SWITCH_HIGH);
+        break;
+
+    case AUX_SWITCH_PARACHUTE_RELEASE:
+        if (ch_flag == AUX_SWITCH_HIGH) {
+            parachute_release();
+        }
+        break;
+
+    case AUX_SWITCH_PARACHUTE_3POS:
+        // Parachute disable, enable, release with 3 position switch
+        switch (ch_flag) {
+            case AUX_SWITCH_LOW:
+                parachute.enabled(false);
+                break;
+            case AUX_SWITCH_MIDDLE:
+                parachute.enabled(true);
+                break;
+            case AUX_SWITCH_HIGH:
+                parachute.enabled(true);
+                parachute_release();
+                break;
+        }
+#endif
     }
 }
 
diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h
index 58ec8134b067c861b6904da1251f93a7b463b329..1943ddc7b5f6040c31f72393272fb54edd712d96 100644
--- a/ArduCopter/defines.h
+++ b/ArduCopter/defines.h
@@ -53,6 +53,9 @@
 #define AUX_SWITCH_LAND             18      // change to LAND flight mode
 #define AUX_SWITCH_EPM              19      // Operate the EPM cargo gripper low=off, middle=neutral, high=on
 #define AUX_SWITCH_EKF              20      // Enable NavEKF
+#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
 
 // 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)