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.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.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.h"1617#if HAL_EFI_ENABLED1819#include "AP_EFI_Serial_MS.h"20#include "AP_EFI_Serial_Lutan.h"21#include "AP_EFI_NWPMU.h"22#include "AP_EFI_DroneCAN.h"23#include "AP_EFI_Currawong_ECU.h"24#include "AP_EFI_Serial_Hirth.h"25#include "AP_EFI_Scripting.h"26#include "AP_EFI_MAV.h"2728#include <AP_Logger/AP_Logger.h>29#include <GCS_MAVLink/GCS.h>30#include <AP_Math/AP_Math.h>3132#if HAL_MAX_CAN_PROTOCOL_DRIVERS33#include <AP_CANManager/AP_CANManager.h>34#endif3536extern const AP_HAL::HAL& hal;3738// table of user settable parameters39const AP_Param::GroupInfo AP_EFI::var_info[] = {40// @Param: _TYPE41// @DisplayName: EFI communication type42// @Description: What method of communication is used for EFI #143// @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth,9:MAVLink44// @User: Advanced45// @RebootRequired: True46AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE),4748// @Param: _COEF149// @DisplayName: EFI Calibration Coefficient 150// @Description: Used to calibrate fuel flow for MS protocol (Slope). This should be calculated from a log at constant fuel usage rate. Plot (ECYL[0].InjT*EFI.Rpm)/600.0 to get the duty_cycle. Measure actual fuel usage in cm^3/min, and set EFI_COEF1 = fuel_usage_cm3permin / duty_cycle51// @Range: 0 152// @User: Advanced53AP_GROUPINFO("_COEF1", 2, AP_EFI, coef1, 0),5455// @Param: _COEF256// @DisplayName: EFI Calibration Coefficient 257// @Description: Used to calibrate fuel flow for MS protocol (Offset). This can be used to correct for a non-zero offset in the fuel consumption calculation of EFI_COEF158// @Range: 0 1059// @User: Advanced60AP_GROUPINFO("_COEF2", 3, AP_EFI, coef2, 0),6162// @Param: _FUEL_DENS63// @DisplayName: ECU Fuel Density64// @Description: Used to calculate fuel consumption65// @Units: kg/m/m/m66// @Range: 0 1000067// @User: Advanced68AP_GROUPINFO("_FUEL_DENS", 4, AP_EFI, ecu_fuel_density, 0),6970#if AP_EFI_THROTTLE_LINEARISATION_ENABLED71// @Group: _THRLIN72// @Path: AP_EFI_ThrottleLinearisation.cpp73AP_SUBGROUPINFO(throttle_linearisation, "_THRLIN", 5, AP_EFI, AP_EFI_ThrLin),74#endif7576AP_GROUPEND77};7879AP_EFI *AP_EFI::singleton;8081// Initialize parameters82AP_EFI::AP_EFI()83{84singleton = this;85AP_Param::setup_object_defaults(this, var_info);86}8788// Initialize backends based on existing params89void AP_EFI::init(void)90{91if (backend != nullptr) {92// Init called twice, perhaps93return;94}95switch ((Type)type.get()) {96case Type::NONE:97break;98#if AP_EFI_SERIAL_MS_ENABLED99case Type::MegaSquirt:100backend = NEW_NOTHROW AP_EFI_Serial_MS(*this);101break;102#endif103#if AP_EFI_SERIAL_LUTAN_ENABLED104case Type::Lutan:105backend = NEW_NOTHROW AP_EFI_Serial_Lutan(*this);106break;107#endif108#if AP_EFI_NWPWU_ENABLED109case Type::NWPMU:110backend = NEW_NOTHROW AP_EFI_NWPMU(*this);111break;112#endif113#if AP_EFI_DRONECAN_ENABLED114case Type::DroneCAN:115backend = NEW_NOTHROW AP_EFI_DroneCAN(*this);116break;117#endif118#if AP_EFI_CURRAWONG_ECU_ENABLED119case Type::CurrawongECU:120backend = NEW_NOTHROW AP_EFI_Currawong_ECU(*this);121break;122#endif123#if AP_EFI_SCRIPTING_ENABLED124case Type::SCRIPTING:125backend = NEW_NOTHROW AP_EFI_Scripting(*this);126break;127#endif128#if AP_EFI_SERIAL_HIRTH_ENABLED129case Type::Hirth:130backend = NEW_NOTHROW AP_EFI_Serial_Hirth(*this);131break;132#endif133#if AP_EFI_MAV_ENABLED134case Type::MAV:135backend = NEW_NOTHROW AP_EFI_MAV(*this);136break;137#endif138default:139GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown EFI type");140break;141}142}143144// Ask all backends to update the frontend145void AP_EFI::update()146{147if (backend) {148backend->update();149#if HAL_LOGGING_ENABLED150log_status();151#endif152}153}154155bool AP_EFI::is_healthy(void) const156{157return (backend && (AP_HAL::millis() - state.last_updated_ms) < HEALTHY_LAST_RECEIVED_MS);158}159160#if HAL_LOGGING_ENABLED161/*162write status to log163*/164void AP_EFI::log_status(void)165{166// @LoggerMessage: EFI167// @Description: Electronic Fuel Injection system data168// @Field: TimeUS: Time since system startup169// @Field: LP: Reported engine load170// @Field: Rpm: Reported engine RPM171// @Field: SDT: Spark Dwell Time172// @Field: ATM: Atmospheric pressure173// @Field: IMP: Intake manifold pressure174// @Field: IMT: Intake manifold temperature175// @Field: ECT: Engine Coolant Temperature176// @Field: OilP: Oil Pressure177// @Field: OilT: Oil temperature178// @Field: FP: Fuel Pressure179// @Field: FCR: Fuel Consumption Rate180// @Field: CFV: Consumed fueld volume181// @Field: TPS: Throttle Position182// @Field: IDX: Index of the publishing ECU183AP::logger().WriteStreaming("EFI",184"TimeUS,LP,Rpm,SDT,ATM,IMP,IMT,ECT,OilP,OilT,FP,FCR,CFV,TPS,IDX",185"s%qsPPOOPOP--%-",186"F00C--00-0-0000",187"QBIffffffffffBB",188AP_HAL::micros64(),189uint8_t(state.engine_load_percent),190uint32_t(state.engine_speed_rpm),191float(state.spark_dwell_time_ms),192float(state.atmospheric_pressure_kpa),193float(state.intake_manifold_pressure_kpa),194float(state.intake_manifold_temperature),195float(state.coolant_temperature),196float(state.oil_pressure),197float(state.oil_temperature),198float(state.fuel_pressure),199float(state.fuel_consumption_rate_cm3pm),200float(state.estimated_consumed_fuel_volume_cm3),201uint8_t(state.throttle_position_percent),202uint8_t(state.ecu_index));203204// @LoggerMessage: EFI2205// @Description: Electronic Fuel Injection system data - redux206// @Field: TimeUS: Time since system startup207// @Field: Healthy: True if EFI is healthy208// @Field: ES: Engine state209// @Field: GE: General error210// @Field: CSE: Crankshaft sensor status211// @Field: TS: Temperature status212// @Field: FPS: Fuel pressure status213// @Field: OPS: Oil pressure status214// @Field: DS: Detonation status215// @Field: MS: Misfire status216// @Field: DebS: Debris status217// @Field: SPU: Spark plug usage218// @Field: IDX: Index of the publishing ECU219AP::logger().WriteStreaming("EFI2",220"TimeUS,Healthy,ES,GE,CSE,TS,FPS,OPS,DS,MS,DebS,SPU,IDX",221"s------------",222"F------------",223"QBBBBBBBBBBBB",224AP_HAL::micros64(),225uint8_t(is_healthy()),226uint8_t(state.engine_state),227uint8_t(state.general_error),228uint8_t(state.crankshaft_sensor_status),229uint8_t(state.temperature_status),230uint8_t(state.fuel_pressure_status),231uint8_t(state.oil_pressure_status),232uint8_t(state.detonation_status),233uint8_t(state.misfire_status),234uint8_t(state.debris_status),235uint8_t(state.spark_plug_usage),236uint8_t(state.ecu_index));237238// @LoggerMessage: ECYL239// @Description: EFI per-cylinder information240// @Field: TimeUS: Time since system startup241// @Field: Inst: Cylinder this data belongs to242// @Field: IgnT: Ignition timing243// @Field: InjT: Injection time244// @Field: CHT: Cylinder head temperature245// @Field: EGT: Exhaust gas temperature246// @Field: Lambda: Estimated lambda coefficient (dimensionless ratio)247// @Field: CHT2: Cylinder2 head temperature248// @Field: EGT2: Cylinder2 Exhaust gas temperature249// @Field: IDX: Index of the publishing ECU250AP::logger().WriteStreaming("ECYL",251"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX",252"s#dsOO-OO-",253"F-0C000000",254"QBffffffff",255AP_HAL::micros64(),2560,257state.cylinder_status.ignition_timing_deg,258state.cylinder_status.injection_time_ms,259KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature),260KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),261state.cylinder_status.lambda_coefficient,262KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature2),263KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature2),264state.ecu_index);265}266#endif // LOGGING_ENABLED267268/*269send EFI_STATUS270*/271void AP_EFI::send_mavlink_status(mavlink_channel_t chan)272{273if (!backend) {274return;275}276277float ignition_voltage;278if (isnan(state.ignition_voltage) ||279is_equal(state.ignition_voltage, -1.0f)) {280// zero means "unknown" in mavlink, 0.0001 means 0 volts281ignition_voltage = 0;282} else if (is_zero(state.ignition_voltage)) {283// zero means "unknown" in mavlink, 0.0001 means 0 volts284ignition_voltage = 0.0001f;285} else {286ignition_voltage = state.ignition_voltage;287};288289// If fuel pressure is supported, but is exactly zero, shift it to 0.0001290// to indicate that it is supported.291float fuel_pressure = state.fuel_pressure;292if (is_zero(fuel_pressure) && state.fuel_pressure_status != Fuel_Pressure_Status::NOT_SUPPORTED) {293fuel_pressure = 0.0001;294}295296mavlink_msg_efi_status_send(297chan,298AP_EFI::is_healthy(),299state.ecu_index,300state.engine_speed_rpm,301state.estimated_consumed_fuel_volume_cm3,302state.fuel_consumption_rate_cm3pm,303state.engine_load_percent,304state.throttle_position_percent,305state.spark_dwell_time_ms,306state.atmospheric_pressure_kpa,307state.intake_manifold_pressure_kpa,308KELVIN_TO_C(state.intake_manifold_temperature),309KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature),310state.cylinder_status.ignition_timing_deg,311state.cylinder_status.injection_time_ms,312KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),313state.throttle_out,314state.pt_compensation,315ignition_voltage,316fuel_pressure317);318}319320// get a copy of state structure321void AP_EFI::get_state(EFI_State &_state)322{323WITH_SEMAPHORE(sem);324_state = state;325}326327void AP_EFI::handle_EFI_message(const mavlink_message_t &msg) {328if (backend != nullptr) {329backend->handle_EFI_message(msg);330}331}332333namespace AP {334AP_EFI *EFI()335{336return AP_EFI::get_singleton();337}338}339340#endif // HAL_EFI_ENABLED341342343344