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_Currawong_ECU.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/*16* AP_EFI_Currawong_ECU.cpp17*18* Author: Reilly Callaway / Currawong Engineering Pty Ltd19*/2021#include "AP_EFI_Currawong_ECU.h"2223#if AP_EFI_CURRAWONG_ECU_ENABLED2425#include <AP_Param/AP_Param.h>26#include <AP_PiccoloCAN/piccolo_protocol/ECUPackets.h>27#include <AP_Math/definitions.h>2829AP_EFI_Currawong_ECU* AP_EFI_Currawong_ECU::_singleton;3031AP_EFI_Currawong_ECU::AP_EFI_Currawong_ECU(AP_EFI &_frontend) :32AP_EFI_Backend(_frontend)33{34_singleton = this;3536// Indicate that temperature and fuel pressure are supported37internal_state.fuel_pressure_status = Fuel_Pressure_Status::OK;38internal_state.temperature_status = Temperature_Status::OK;3940// Currawong ECU does not report EGT41internal_state.cylinder_status.exhaust_gas_temperature = NAN;4243}4445void AP_EFI_Currawong_ECU::update()46{47// copy the data to the front end48copy_to_frontend();49}5051bool AP_EFI_Currawong_ECU::handle_message(AP_HAL::CANFrame &frame)52{53bool valid = true;5455// There are differences between Ardupilot EFI_State and types/scaling of Piccolo packets.56// First decode to Piccolo structs, and then store the data we need in internal_state with any scaling required.5758// Structs to decode Piccolo messages into59ECU_TelemetryFast_t telemetry_fast;60ECU_TelemetrySlow0_t telemetry_slow0;61ECU_TelemetrySlow1_t telemetry_slow1;62ECU_TelemetrySlow2_t telemetry_slow2;6364// Throw the message at the decoding functions65if (decodeECU_TelemetryFastPacketStructure(&frame, &telemetry_fast)) {66internal_state.throttle_position_percent = static_cast<uint8_t>(telemetry_fast.throttle);67internal_state.engine_load_percent = static_cast<uint8_t>(telemetry_fast.throttle);68internal_state.engine_speed_rpm = static_cast<uint32_t>(telemetry_fast.rpm);6970if (internal_state.engine_speed_rpm > 0) {71internal_state.engine_state = Engine_State::RUNNING;72} else {73internal_state.engine_state = Engine_State::STOPPED;74}7576// Prevent div by zero77if (get_ecu_fuel_density() > 0.01) {78internal_state.estimated_consumed_fuel_volume_cm3 = static_cast<float>(telemetry_fast.fuelUsed) / KG_PER_M3_TO_G_PER_CM3(get_ecu_fuel_density());79} else {80// If no (reasonable) density is provided81internal_state.estimated_consumed_fuel_volume_cm3 = 0.;82}8384internal_state.general_error = telemetry_fast.ecuStatusBits.errorIndicator;85if (!telemetry_fast.ecuStatusBits.enabled) {86internal_state.engine_state = Engine_State::STOPPED;87}88} else if (decodeECU_TelemetrySlow0PacketStructure(&frame, &telemetry_slow0)) {89internal_state.intake_manifold_pressure_kpa = telemetry_slow0.map;90internal_state.atmospheric_pressure_kpa = telemetry_slow0.baro;91internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(telemetry_slow0.cht);92} else if (decodeECU_TelemetrySlow1PacketStructure(&frame, &telemetry_slow1)) {93internal_state.intake_manifold_temperature = C_TO_KELVIN(telemetry_slow1.mat);94internal_state.fuel_pressure = telemetry_slow1.fuelPressure;95} else if (decodeECU_TelemetrySlow2PacketStructure(&frame, &telemetry_slow2)) {96internal_state.cylinder_status.ignition_timing_deg = telemetry_slow2.ignAngle1;9798internal_state.fuel_consumption_rate_cm3pm = telemetry_slow2.flowRate / KG_PER_M3_TO_G_PER_CM3(get_ecu_fuel_density());99} else {100valid = false;101}102103if (valid) {104internal_state.last_updated_ms = AP_HAL::millis();105}106107return valid;108}109110#endif // AP_EFI_CURRAWONG_ECU_ENABLED111112113