mirror of https://github.com/ArduPilot/ardupilot
AP_ServoRelayEvents: add option to disable relay and servorelay libraries
This commit is contained in:
parent
f96266b227
commit
27c3f8525d
|
@ -16,6 +16,9 @@
|
|||
* AP_ServoRelayEvents - handle servo and relay MAVLink events
|
||||
*/
|
||||
|
||||
#include "AP_ServoRelayEvents_config.h"
|
||||
|
||||
#if AP_SERVORELAYEVENTS_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
@ -55,6 +58,7 @@ bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm)
|
|||
return true;
|
||||
}
|
||||
|
||||
#if AP_RELAY_ENABLED
|
||||
bool AP_ServoRelayEvents::do_set_relay(uint8_t relay_num, uint8_t state)
|
||||
{
|
||||
AP_Relay *relay = AP::relay();
|
||||
|
@ -79,6 +83,7 @@ bool AP_ServoRelayEvents::do_set_relay(uint8_t relay_num, uint8_t state)
|
|||
}
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_value,
|
||||
int16_t _repeat, uint16_t _delay_ms)
|
||||
|
@ -111,6 +116,7 @@ bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_valu
|
|||
return true;
|
||||
}
|
||||
|
||||
#if AP_RELAY_ENABLED
|
||||
bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, uint32_t _delay_ms)
|
||||
{
|
||||
AP_Relay *relay = AP::relay();
|
||||
|
@ -128,6 +134,7 @@ bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, ui
|
|||
update_events();
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/*
|
||||
|
@ -155,6 +162,7 @@ void AP_ServoRelayEvents::update_events(void)
|
|||
break;
|
||||
}
|
||||
|
||||
#if AP_RELAY_ENABLED
|
||||
case EVENT_TYPE_RELAY: {
|
||||
AP_Relay *relay = AP::relay();
|
||||
if (relay != nullptr) {
|
||||
|
@ -162,6 +170,7 @@ void AP_ServoRelayEvents::update_events(void)
|
|||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
if (repeat > 0) {
|
||||
repeat--;
|
||||
|
@ -182,3 +191,5 @@ AP_ServoRelayEvents *servorelayevents()
|
|||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_SERVORELAYEVENTS_ENABLED
|
||||
|
|
|
@ -6,13 +6,19 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_ServoRelayEvents_config.h"
|
||||
|
||||
#if AP_SERVORELAYEVENTS_ENABLED
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Relay/AP_Relay.h>
|
||||
|
||||
class AP_ServoRelayEvents {
|
||||
public:
|
||||
AP_ServoRelayEvents()
|
||||
#if AP_RELAY_ENABLED
|
||||
: type(EVENT_TYPE_RELAY)
|
||||
#endif
|
||||
{
|
||||
_singleton = this;
|
||||
}
|
||||
|
@ -26,7 +32,9 @@ public:
|
|||
}
|
||||
|
||||
bool do_set_servo(uint8_t channel, uint16_t pwm);
|
||||
#if AP_RELAY_ENABLED
|
||||
bool do_set_relay(uint8_t relay_num, uint8_t state);
|
||||
#endif
|
||||
bool do_repeat_servo(uint8_t channel, uint16_t servo_value, int16_t repeat, uint16_t delay_time_ms);
|
||||
bool do_repeat_relay(uint8_t relay_num, int16_t count, uint32_t period_ms);
|
||||
void update_events(void);
|
||||
|
@ -37,7 +45,9 @@ private:
|
|||
|
||||
// event control state
|
||||
enum event_type {
|
||||
#if AP_RELAY_ENABLED
|
||||
EVENT_TYPE_RELAY=0,
|
||||
#endif
|
||||
EVENT_TYPE_SERVO=1
|
||||
};
|
||||
|
||||
|
@ -62,3 +72,5 @@ private:
|
|||
namespace AP {
|
||||
AP_ServoRelayEvents *servorelayevents();
|
||||
};
|
||||
|
||||
#endif // AP_SERVORELAYEVENTS_ENABLED
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_SERVORELAYEVENTS_ENABLED
|
||||
#define AP_SERVORELAYEVENTS_ENABLED 1
|
||||
#endif
|
Loading…
Reference in New Issue