Browse Source

Copter: fixes for AP_Relay API change

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
e3804e2846
  1. 4
      ArduCopter/ArduCopter.pde
  2. 6
      ArduCopter/commands_logic.pde
  3. 2
      ArduCopter/events.pde
  4. 4
      ArduCopter/test.pde

4
ArduCopter/ArduCopter.pde

@ -2205,8 +2205,8 @@ static void tuning(){ @@ -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

6
ArduCopter/commands_logic.pde

@ -906,11 +906,11 @@ static void do_set_servo() @@ -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);
}
}

2
ArduCopter/events.pde

@ -324,7 +324,7 @@ static void update_events() // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_ @@ -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--;

4
ArduCopter/test.pde

@ -495,14 +495,14 @@ static int8_t test_relay(uint8_t argc, const Menu::arg *argv) @@ -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);

Loading…
Cancel
Save