mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Moved relay control functions to it's own library
This commit is contained in:
parent
eba281e3de
commit
4b35757a1e
@ -41,6 +41,7 @@ version 2.1 of the License, or (at your option) any later version.
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <ModeFilter.h>
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <memcheck.h>
|
||||
|
||||
@ -400,6 +401,7 @@ static unsigned long dTnav; // Delta Time in milliseconds for navigation c
|
||||
static float load; // % MCU cycles used
|
||||
|
||||
RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function
|
||||
AP_Relay relay;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Top-level logic
|
||||
|
@ -483,11 +483,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();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -104,23 +104,7 @@ static void update_events(void) // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
|
46
libraries/AP_Relay/AP_Relay.cpp
Normal file
46
libraries/AP_Relay/AP_Relay.cpp
Normal file
@ -0,0 +1,46 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/*
|
||||
* AP_Relay.cpp
|
||||
*
|
||||
* Created on: Oct 2, 2011
|
||||
* Author: Amilcar Lucas
|
||||
*/
|
||||
|
||||
#include <avr/io.h>
|
||||
#include "wiring.h"
|
||||
|
||||
#include "AP_Relay.h"
|
||||
|
||||
void AP_Relay::on()
|
||||
{
|
||||
PORTL |= B00000100;
|
||||
}
|
||||
|
||||
|
||||
void AP_Relay::off()
|
||||
{
|
||||
PORTL &= ~B00000100;
|
||||
}
|
||||
|
||||
|
||||
void AP_Relay::toggle()
|
||||
{
|
||||
PORTL ^= B00000100;
|
||||
}
|
||||
|
||||
|
||||
void AP_Relay::set(bool status)
|
||||
{
|
||||
if (status)
|
||||
on();
|
||||
else
|
||||
off();
|
||||
}
|
||||
|
||||
|
||||
bool AP_Relay::get()
|
||||
{
|
||||
// TODO get the relay status
|
||||
return false;
|
||||
}
|
37
libraries/AP_Relay/AP_Relay.h
Normal file
37
libraries/AP_Relay/AP_Relay.h
Normal file
@ -0,0 +1,37 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/*
|
||||
* AP_Relay.h
|
||||
*
|
||||
* Created on: Oct 2, 2011
|
||||
* Author: Amilcar Lucas
|
||||
*/
|
||||
|
||||
/// @file AP_Relay.h
|
||||
/// @brief APM relay control class
|
||||
|
||||
#ifndef AP_RELAY_H_
|
||||
#define AP_RELAY_H_
|
||||
|
||||
/// @class AP_Relay
|
||||
/// @brief Class to manage the APM relay
|
||||
class AP_Relay{
|
||||
public:
|
||||
// activate the relay
|
||||
void on();
|
||||
|
||||
// de-activate the relay
|
||||
void off();
|
||||
|
||||
// toggle the relay status
|
||||
void toggle();
|
||||
|
||||
// set the relay status (on/off)
|
||||
void set(bool status);
|
||||
|
||||
// get the relay status (on/off)
|
||||
bool get();
|
||||
};
|
||||
|
||||
|
||||
#endif /* AP_RELAY_H_ */
|
Loading…
Reference in New Issue
Block a user