Path: blob/master/libraries/AP_EFI/AP_EFI_Loweheiser.cpp
4182 views
/*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#include "AP_EFI_Loweheiser.h"1617#if AP_EFI_LOWEHEISER_ENABLED1819#include <AP_Generator/AP_Generator.h>20#include <AP_Generator/AP_Generator_Loweheiser.h>2122// The Loweheiser EFI backend can be unhealthy not simply because23// we've not gotten an update, but also because it is rejecting our24// (mavlink) commands:25bool AP_EFI_Loweheiser::healthy() const26{27AP_Generator *gen = AP::generator();28if (gen == nullptr) {29return false;30}3132AP_Generator_Loweheiser *backend = gen->get_loweheiser();33if (backend == nullptr) {34return false;35}3637if (!backend->good_ack) {38return false;39}4041return AP_EFI_Backend::healthy();42}4344void AP_EFI_Loweheiser::update()45{46AP_Generator *gen = AP::generator();47if (gen == nullptr) {48return;49}5051AP_Generator_Loweheiser *backend = gen->get_loweheiser();52if (backend == nullptr) {53return;54}5556if (backend->last_packet_received_ms == internal_state.last_updated_ms) {57return;58}5960// AP_Generator_Loweheiser remembers the last packet we got from61// the generator as a convenient way of storing data we may wish62// to relay:63const mavlink_loweheiser_gov_efi_t &pkt = backend->packet;6465// this list is ordered by the field order in the66// LOWEHEISER_GOV_EFI message. These fields become NaN when the67// EFI is powered off. This is the case when the generator68// control switch is in the "don't run" position.69if (isnan(pkt.throttle)) {70// this is an integer field in internal_state71internal_state.throttle_out = 0;72} else {73internal_state.throttle_out = pkt.throttle;74}75// pkt.efi_batt is used in battery monitoring76if (isnan(pkt.efi_rpm)) {77// this is an integer field in internal_state78internal_state.engine_speed_rpm = 0;79} else {80internal_state.engine_speed_rpm = pkt.efi_rpm;81}82internal_state.cylinder_status.injection_time_ms = pkt.efi_pw;83// we convert to cubic-cm-per-minute here from litres/second here:84internal_state.fuel_consumption_rate_cm3pm = pkt.efi_fuel_flow*(1000/60.0);85internal_state.estimated_consumed_fuel_volume_cm3 = backend->fuel_consumed() * 1000;;86internal_state.intake_manifold_pressure_kpa = pkt.efi_baro;87internal_state.intake_manifold_temperature = C_TO_KELVIN(pkt.efi_mat);88internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(pkt.efi_clt);89internal_state.cylinder_status.exhaust_gas_temperature = C_TO_KELVIN(pkt.efi_exhaust_gas_temperature);90if (isnan(pkt.efi_tps)) {91// this is an integer field in internal_state92internal_state.throttle_position_percent = 0;93} else {94internal_state.throttle_position_percent = pkt.efi_tps;95}96internal_state.ignition_voltage = pkt.efi_batt;9798internal_state.last_updated_ms = backend->last_packet_received_ms;99100// copy the data to the front end101copy_to_frontend();102}103104#endif // AP_EFI_LOWEHEISER_ENABLED105106107