Browse Source

Use the new AP_Relay library

master
Amilcar Lucas 14 years ago
parent
commit
3d1902abac
  1. 5
      ArduCopter/ArduCopter.pde
  2. 6
      ArduCopter/commands_logic.pde
  3. 17
      ArduCopter/events.pde

5
ArduCopter/ArduCopter.pde

@ -65,6 +65,7 @@ And much more so PLEASE PM me on DIYDRONES to add your contribution to the List @@ -65,6 +65,7 @@ And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
#include <AP_RangeFinder.h> // Range finder library
#include <AP_OpticalFlow.h> // Optical Flow library
#include <ModeFilter.h>
#include <AP_Relay.h> // APM relay
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <memcheck.h>
@ -1313,8 +1314,8 @@ static void tuning(){ @@ -1313,8 +1314,8 @@ static void tuning(){
case CH6_RELAY:
g.rc_6.set_range(0,1000);
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();
if (g.rc_6.control_in < 475) relay.off();
break;
case CH6_TRAVERSE_SPEED:

6
ArduCopter/commands_logic.pde

@ -693,11 +693,11 @@ static void do_set_servo() @@ -693,11 +693,11 @@ static void do_set_servo()
static void do_set_relay()
{
if (next_command.p1 == 1) {
relay_on();
relay.on();
} else if (next_command.p1 == 0) {
relay_off();
relay.off();
}else{
relay_toggle();
relay.toggle();
}
}

17
ArduCopter/events.pde

@ -75,26 +75,11 @@ static void update_events() // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_R @@ -75,26 +75,11 @@ static void update_events() // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_R
}
if (event_id == RELAY_TOGGLE) {
relay_toggle();
relay.toggle();
}
}
}
static void relay_on()
{
PORTL |= B00000100;
}
static void relay_off()
{
PORTL &= ~B00000100;
}
static void relay_toggle()
{
PORTL ^= B00000100;
}
#if PIEZO == ENABLED
void piezo_on()
{

Loading…
Cancel
Save