ardupilot/libraries/AP_Relay/AP_Relay.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

142 lines
3.5 KiB
C
Raw Normal View History

/*
* AP_Relay.h
*
* Created on: Oct 2, 2011
* Author: Amilcar Lucas
*/
/// @file AP_Relay.h
/// @brief APM relay control class
#pragma once
#include "AP_Relay_config.h"
#if AP_RELAY_ENABLED
#include <AP_Param/AP_Param.h>
#include <AP_Relay/AP_Relay_Params.h>
#include <AP_Common/Bitmask.h>
#ifndef AP_RELAY_NUM_RELAYS
#define AP_RELAY_NUM_RELAYS 6
#endif
#if AP_RELAY_NUM_RELAYS < 1
#error There must be at least one relay instance if using AP_Relay
#endif
2014-01-19 21:59:21 -04:00
#if AP_RELAY_DRONECAN_ENABLED
#include <AP_DroneCAN/AP_DroneCAN.h>
#endif
/// @class AP_Relay
2017-08-29 15:08:41 -03:00
/// @brief Class to manage the ArduPilot relay
class AP_Relay {
#if AP_RELAY_DRONECAN_ENABLED
// Allow DroneCAN to directly access private DroneCAN state
friend class AP_DroneCAN;
#endif
public:
AP_Relay();
2017-08-29 15:08:41 -03:00
/* Do not allow copies */
2022-09-30 06:50:43 -03:00
CLASS_NO_COPY(AP_Relay);
2012-12-04 19:26:30 -04:00
// setup the relay pin
void init();
// activate the relay
void on(uint8_t instance) { set(instance, true); }
// de-activate the relay
void off(uint8_t instance) { set(instance, false); }
// get state of relay
bool get(uint8_t instance) const;
2014-01-20 00:35:38 -04:00
// see if the relay is enabled
bool enabled(uint8_t instance) const;
2014-01-20 00:35:38 -04:00
// toggle the relay status
void toggle(uint8_t instance);
2021-07-20 01:26:33 -03:00
// check settings are valid
bool arming_checks(size_t buflen, char *buffer) const;
2019-04-22 20:12:56 -03:00
static AP_Relay *get_singleton(void) {return singleton; }
static const struct AP_Param::GroupInfo var_info[];
bool send_relay_status(const class GCS_MAVLINK &link) const;
2023-12-12 10:02:14 -04:00
void set(AP_Relay_Params::FUNCTION function, bool value);
// see if the relay is enabled
2023-12-12 10:02:14 -04:00
bool enabled(AP_Relay_Params::FUNCTION function) const;
private:
2019-04-22 20:12:56 -03:00
static AP_Relay *singleton;
AP_Relay_Params _params[AP_RELAY_NUM_RELAYS];
// Return true is function is valid
bool function_valid(AP_Relay_Params::FUNCTION function) const;
void set(uint8_t instance, bool value);
void set_defaults();
void convert_params();
void set_pin_by_instance(uint8_t instance, bool value);
// Set relay state from pin number
void set_pin(const int16_t pin, const bool value);
// Get relay state from pin number
bool get_pin(const int16_t pin) const;
#if HAL_ENABLE_DRONECAN_DRIVERS
// Virtual DroneCAN pins
class DroneCAN {
public:
// Return true if pin number is a virtual DroneCAN pin
bool valid_pin(int16_t pin) const;
// Enable streaming of pin number
void enable_pin(int16_t pin);
// Populate message and update index with the sent command
bool populate_next_command(uint8_t &index, uavcan_equipment_hardpoint_Command &msg) const;
// Set DroneCAN relay state from pin number
void set_pin(const int16_t pin, const bool value);
// Get relay state from pin number
bool get_pin(const int16_t pin) const;
private:
// Get the hardpoint index of given pin number
uint8_t hardpoint_index(const int16_t pin) const;
// Send DroneCAN hardpoint message for given index on all interfaces
void send_index(const uint8_t index);
static constexpr uint8_t num_pins = (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_15 - (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_0;
struct {
bool value;
bool enabled;
} state[num_pins];
} dronecan;
#endif // HAL_ENABLE_DRONECAN_DRIVERS
};
namespace AP {
AP_Relay *relay();
};
#endif // AP_RELAY_ENABLED