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_MAV.cpp
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.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/1213#include "AP_EFI_config.h"1415#if AP_EFI_MAV_ENABLED1617#include "AP_EFI_MAV.h"18#include <AP_Math/AP_Math.h>1920//Called from frontend to update with the readings received by handler21void AP_EFI_MAV::update()22{23if (receivedNewData) {24copy_to_frontend();25receivedNewData = false;26}27}2829//Decode MavLink message30void AP_EFI_MAV::handle_EFI_message(const mavlink_message_t &msg)31{32mavlink_efi_status_t state;33mavlink_msg_efi_status_decode(&msg, &state);3435internal_state.ecu_index = state.ecu_index;36internal_state.engine_speed_rpm = state.rpm;37internal_state.estimated_consumed_fuel_volume_cm3 = state.fuel_consumed;38internal_state.fuel_consumption_rate_cm3pm = state.fuel_flow;39internal_state.engine_load_percent = state.engine_load;40internal_state.throttle_position_percent = state.throttle_position;41internal_state.spark_dwell_time_ms = state.spark_dwell_time;42internal_state.atmospheric_pressure_kpa = state.barometric_pressure;43internal_state.intake_manifold_pressure_kpa = state.intake_manifold_pressure;44internal_state.intake_manifold_temperature = C_TO_KELVIN(state.intake_manifold_temperature);45internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(state.cylinder_head_temperature);46internal_state.cylinder_status.ignition_timing_deg = state.ignition_timing;47internal_state.cylinder_status.injection_time_ms = state.injection_time;48internal_state.cylinder_status.exhaust_gas_temperature = C_TO_KELVIN(state.exhaust_gas_temperature);49internal_state.throttle_out = state.throttle_out;50internal_state.pt_compensation = state.pt_compensation;51//internal_state.??? = state.health;52internal_state.ignition_voltage = state.ignition_voltage;5354receivedNewData = true;55}5657#endif // AP_EFI_MAV_ENABLED585960