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_Serial_Lutan.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_config.h"1617#if AP_EFI_SERIAL_LUTAN_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include <AP_HAL/utility/sparse-endian.h>21#include <AP_Math/AP_Math.h>22#include <AP_SerialManager/AP_SerialManager.h>2324#include "AP_EFI_Serial_Lutan.h"2526#include <stdio.h>2728// RPM Threshold for fuel consumption estimator29#define RPM_THRESHOLD 1003031extern const AP_HAL::HAL &hal;3233AP_EFI_Serial_Lutan::AP_EFI_Serial_Lutan(AP_EFI &_frontend):34AP_EFI_Backend(_frontend)35{36port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_EFI, 0);37}383940void AP_EFI_Serial_Lutan::update()41{42if (port == nullptr) {43return;44}4546const uint32_t now = AP_HAL::millis();47if (pkt_nbytes > 0 && now - last_recv_ms > 100) {48pkt_nbytes = 0;49}50const uint32_t n = MIN(sizeof(pkt), port->available());51if (n > 0) {52last_recv_ms = now;53}54if (n + pkt_nbytes > sizeof(pkt)) {55pkt_nbytes = 0;56}57ssize_t nread = port->read(&pkt[pkt_nbytes], n);58if (nread < 0) {59nread = 0;60}61pkt_nbytes += nread;62if (pkt_nbytes > 2) {63const uint16_t length = be16toh(data.length);64if (length+6 == pkt_nbytes) {65// got a pkt of right length66const uint32_t crc = be32toh_ptr(&pkt[length+2]);67const uint32_t crc2 = ~crc_crc32(~0U, &pkt[2], length);68if (crc == crc2) {69// valid data70internal_state.spark_dwell_time_ms = int16_t(be16toh(data.dwell))*0.1;71internal_state.cylinder_status.injection_time_ms = be16toh(data.pulseWidth1)*0.00666;72internal_state.engine_speed_rpm = be16toh(data.rpm);73internal_state.atmospheric_pressure_kpa = int16_t(be16toh(data.barometer))*0.1;74internal_state.intake_manifold_pressure_kpa = int16_t(be16toh(data.map))*0.1;75internal_state.intake_manifold_temperature = degF_to_Kelvin(int16_t(be16toh(data.mat))*0.1);76internal_state.coolant_temperature = degF_to_Kelvin(int16_t(be16toh(data.coolant))*0.1);77// CHT is in coolant field78internal_state.cylinder_status.cylinder_head_temperature = internal_state.coolant_temperature;79internal_state.throttle_position_percent = int16_t(be16toh(data.tps))*0.1;8081// integrate fuel consumption82if (internal_state.engine_speed_rpm > RPM_THRESHOLD) {83const float duty_cycle = (internal_state.cylinder_status.injection_time_ms * internal_state.engine_speed_rpm)/600.0f;84internal_state.fuel_consumption_rate_cm3pm = duty_cycle*get_coef1() - get_coef2();85internal_state.estimated_consumed_fuel_volume_cm3 += internal_state.fuel_consumption_rate_cm3pm * (now - internal_state.last_updated_ms)/60000.0f;86} else {87internal_state.fuel_consumption_rate_cm3pm = 0;88}89internal_state.last_updated_ms = now;90copy_to_frontend();91}92pkt_nbytes = 0;93}94}95if (now - last_request_ms > 200) {96last_request_ms = now;97port->discard_input();98send_request();99}100}101102void AP_EFI_Serial_Lutan::send_request(void)103{104static const uint8_t d[] = { 0, 1, 0x41 };105const uint32_t crc = ~crc_crc32(~0U, &d[2], sizeof(d)-2);106const uint32_t crc2 = htobe32(crc);107port->write(d, sizeof(d));108port->write((const uint8_t *)&crc2, sizeof(crc2));109}110111#endif // AP_EFI_SERIAL_LUTAN_ENABLED112113114