/* * 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 #include #include #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 #if AP_RELAY_DRONECAN_ENABLED #include #endif /// @class AP_Relay /// @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(); /* Do not allow copies */ CLASS_NO_COPY(AP_Relay); // 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; // see if the relay is enabled bool enabled(uint8_t instance) const; // toggle the relay status void toggle(uint8_t instance); // check settings are valid bool arming_checks(size_t buflen, char *buffer) const; 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; void set(AP_Relay_Params::FUNCTION function, bool value); // see if the relay is enabled bool enabled(AP_Relay_Params::FUNCTION function) const; private: 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