Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_EFI/AP_EFI_Backend.h
Views: 1798
/*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*/14#pragma once1516#include "AP_EFI.h"17#include "AP_EFI_State.h"18#include <AP_HAL/Semaphores.h>19#include <AP_Scripting/AP_Scripting_config.h>20#include <GCS_MAVLink/GCS_MAVLink.h>2122class AP_EFI; //forward declaration2324class AP_EFI_Backend {25public:26// Constructor with initialization27AP_EFI_Backend(AP_EFI &_frontend);2829// Virtual destructor that efi backends can override30virtual ~AP_EFI_Backend(void) {}3132// Update the state structure33virtual void update() = 0;3435virtual void handle_EFI_message(const mavlink_message_t &msg) {};3637#if AP_SCRIPTING_ENABLED38virtual bool handle_scripting(const EFI_State &efi_state) { return false; }39#endif4041protected:42// Copies internal state to the frontend state43void copy_to_frontend();4445// Internal state for this driver (before copying to frontend)46EFI_State internal_state;4748int8_t get_dronecan_node_id(void) const;49float get_coef1(void) const;50float get_coef2(void) const;5152void set_default_coef1(float coef1);5354float get_ecu_fuel_density(void) const;5556/*57linearise throttle if enabled58*/59float linearise_throttle(float throttle_percent);6061HAL_Semaphore &get_sem(void);6263private:64AP_EFI &frontend;65};666768