diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index a9611839c4a3051df46c5fa04fee4b6ae7c6b0cf..1a8bf3d7fd9facdbff79835ff13c84403d14c375 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -2205,8 +2205,8 @@ static void tuning(){
         break;
 
     case CH6_RELAY:
-        if (g.rc_6.control_in > 525) relay.on();
-        if (g.rc_6.control_in < 475) relay.off();
+        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
diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde
index 2d331f838ec026de5ad6c9b60b87723fdae019be..b16680b547bde6a20af8a2c3f7b0f5d56b296625 100644
--- a/ArduCopter/commands_logic.pde
+++ b/ArduCopter/commands_logic.pde
@@ -906,11 +906,11 @@ static void do_set_servo()
 static void do_set_relay()
 {
     if (command_cond_queue.p1 == 1) {
-        relay.on();
+        relay.on(0);
     } else if (command_cond_queue.p1 == 0) {
-        relay.off();
+        relay.off(0);
     }else{
-        relay.toggle();
+        relay.toggle(0);
     }
 }
 
diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde
index 13c69776eff561b233f5b3dedbd448be9cce7e92..ce66ffe8845c13c8588ebf52cde02d0ed78bd038 100644
--- a/ArduCopter/events.pde
+++ b/ArduCopter/events.pde
@@ -324,7 +324,7 @@ static void update_events()     // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_
         }
 
         if  (event_id == RELAY_TOGGLE) {
-            relay.toggle();
+            relay.toggle(0);
         }
         if (event_repeat > 0) {
             event_repeat--;
diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde
index 1f7b21ba87be7596ac691f10ae67bce8190fc6d1..3a156b1e1dcb06a49bf4ea5b7b9ed9d8e04bb6ea 100644
--- a/ArduCopter/test.pde
+++ b/ArduCopter/test.pde
@@ -495,14 +495,14 @@ static int8_t test_relay(uint8_t argc, const Menu::arg *argv)
 
     while(1) {
         cliSerial->printf_P(PSTR("Relay on\n"));
-        relay.on();
+        relay.on(0);
         delay(3000);
         if(cliSerial->available() > 0) {
             return (0);
         }
 
         cliSerial->printf_P(PSTR("Relay off\n"));
-        relay.off();
+        relay.off(0);
         delay(3000);
         if(cliSerial->available() > 0) {
             return (0);