/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#pragma once1617#include "AP_EFI_config.h"1819#if HAL_EFI_ENABLED2021#include <AP_Common/AP_Common.h>22#include <AP_Param/AP_Param.h>23#include <GCS_MAVLink/GCS_MAVLink.h>24#include "AP_EFI_ThrottleLinearisation.h"25#include <AP_HAL/AP_HAL_Boards.h>2627#ifndef AP_EFI_LOWEHEISER_ENABLED28#define AP_EFI_LOWEHEISER_ENABLED 029#endif3031#include "AP_EFI_Backend.h"32#include "AP_EFI_State.h"333435/*36* This library aims to read data from Electronic Fuel Injection37* or Engine Control units. It is focused around the generic38* internal combustion engine state message provided by the39* UAVCAN protocol due to its comprehensiveness, but is extensible40* to use other forms of data transfer besides UAVCAN.41*42*43*44* Authors: Sriram Sami and David Ingraham45* With direction from Andrew Tridgell, Robert Lefebvre, Francisco Ferreira and46* Pavel Kirienko.47* Thanks to Yonah, SpektreWorks Inc, and HFE International.48*/4950class AP_EFI {51public:52friend class AP_EFI_Backend;5354// For parameter initialization55AP_EFI();5657// Initializes backend58void init(void);5960// Requests backend to update the frontend. Should be called at 10Hz.61void update();6263// Returns the RPM64uint32_t get_rpm() const { return state.engine_speed_rpm; }6566// returns enabled state of EFI67bool enabled() const { return type != Type::NONE; }6869bool is_healthy() const;7071// return timestamp of last update72uint32_t get_last_update_ms(void) const {73return state.last_updated_ms;74}7576// get a copy of state structure77void get_state(EFI_State &state);7879// Parameter info80static const struct AP_Param::GroupInfo var_info[];8182// Backend driver types83enum class Type : uint8_t {84NONE = 0,85#if AP_EFI_SERIAL_MS_ENABLED86MegaSquirt = 1,87#endif88#if AP_EFI_NWPWU_ENABLED89NWPMU = 2,90#endif91#if AP_EFI_SERIAL_LUTAN_ENABLED92Lutan = 3,93#endif94#if AP_EFI_LOWEHEISER_ENABLED95LOWEHEISER = 4,96#endif97#if AP_EFI_DRONECAN_ENABLED98DroneCAN = 5,99#endif100#if AP_EFI_CURRAWONG_ECU_ENABLED101CurrawongECU = 6,102#endif103#if AP_EFI_SCRIPTING_ENABLED104SCRIPTING = 7,105#endif106#if AP_EFI_SERIAL_HIRTH_ENABLED107Hirth = 8,108#endif109MAV = 9,110};111112static AP_EFI *get_singleton(void) {113return singleton;114}115116// send EFI_STATUS117void send_mavlink_status(mavlink_channel_t chan);118119#if AP_SCRIPTING_ENABLED120AP_EFI_Backend* get_backend(uint8_t idx) { return idx==0?backend:nullptr; }121#endif122123void handle_EFI_message(const mavlink_message_t &msg);124125protected:126127// Back end Parameters128AP_Float coef1;129AP_Float coef2;130131AP_Float ecu_fuel_density;132133EFI_State state;134135#if AP_EFI_THROTTLE_LINEARISATION_ENABLED136AP_EFI_ThrLin throttle_linearisation;137#endif138139private:140// Front End Parameters141AP_Enum<Type> type;142143// Tracking backends144AP_EFI_Backend *backend;145static AP_EFI *singleton;146147// Semaphore for access to shared frontend data148HAL_Semaphore sem;149150// write to log151void log_status();152};153154namespace AP {155AP_EFI *EFI();156};157158#endif // HAL_EFI_ENABLED159160161