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_MS.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_MS_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include <AP_Math/AP_Math.h>21#include <AP_SerialManager/AP_SerialManager.h>2223#include "AP_EFI_Serial_MS.h"2425extern const AP_HAL::HAL &hal;2627AP_EFI_Serial_MS::AP_EFI_Serial_MS(AP_EFI &_frontend):28AP_EFI_Backend(_frontend)29{30internal_state.estimated_consumed_fuel_volume_cm3 = 0; // Just to be sure31port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_EFI, 0);32}333435void AP_EFI_Serial_MS::update()36{37if (!port) {38return;39}4041uint32_t now = AP_HAL::millis();4243const uint32_t expected_bytes = 2 + (RT_LAST_OFFSET - RT_FIRST_OFFSET) + 4;44if (port->available() >= expected_bytes && read_incoming_realtime_data()) {45copy_to_frontend();46}4748const uint32_t last_request_delta = (now - last_request_ms);49const uint32_t available = port->available();50if (((last_request_delta > 150) && (available > 0)) || // nothing in our input buffer 150 ms after request51((last_request_delta > 90) && (available == 0))) { // we requested something over 90 ms ago, but didn't get any data52port->discard_input();53last_request_ms = now;54// Request an update from the realtime table (7).55// The data we need start at offset 6 and ends at 12956send_request(7, RT_FIRST_OFFSET, RT_LAST_OFFSET);57}58}5960bool AP_EFI_Serial_MS::read_incoming_realtime_data()61{62// Data is parsed directly from the buffer, otherwise we would need to allocate63// several hundred bytes for the entire realtime data table or request every64// value individually65uint16_t message_length = 0;6667// reset checksum before reading new data68checksum = 0;6970// Message length field begins the message (16 bits, excluded from CRC calculation)71// Message length value excludes the message length and CRC bytes72message_length = port->read() << 8;73message_length += port->read();7475if (message_length >= 256) {76// don't process invalid messages77// hal.console->printf("message_length: %u\n", message_length);78return false;79}8081// Response Flag (see "response_codes" enum)82response_flag = read_byte_CRC32();83if (response_flag != RESPONSE_WRITE_OK) {84// abort read if we did not receive the correct response code;85return false;86}8788// Iterate over the payload bytes89for (uint16_t offset=RT_FIRST_OFFSET; offset < (RT_FIRST_OFFSET + message_length - 1); offset++) {90uint8_t data = read_byte_CRC32();91float temp_float;92switch (offset) {93case PW1_MSB:94internal_state.cylinder_status.injection_time_ms = (float)((data << 8) + read_byte_CRC32())/1000.0f;95offset++; // increment the counter because we read a byte in the previous line96break;97case RPM_MSB:98// Read 16 bit RPM99internal_state.engine_speed_rpm = (data << 8) + read_byte_CRC32();100offset++;101break;102case ADVANCE_MSB:103internal_state.cylinder_status.ignition_timing_deg = (float)((data << 8) + read_byte_CRC32())*0.1f;104offset++;105break;106case ENGINE_BM:107break;108case BAROMETER_MSB:109internal_state.atmospheric_pressure_kpa = (float)((data << 8) + read_byte_CRC32())*0.1f;110offset++;111break;112case MAP_MSB:113internal_state.intake_manifold_pressure_kpa = (float)((data << 8) + read_byte_CRC32())*0.1f;114offset++;115break;116case MAT_MSB:117temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;118offset++;119internal_state.intake_manifold_temperature = degF_to_Kelvin(temp_float);120break;121case CHT_MSB:122temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;123offset++;124internal_state.cylinder_status.cylinder_head_temperature = degF_to_Kelvin(temp_float);125break;126case TPS_MSB:127temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;128offset++;129internal_state.throttle_position_percent = roundf(temp_float);130break;131case AFR1_MSB:132temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;133offset++;134internal_state.cylinder_status.lambda_coefficient = temp_float;135break;136case DWELL_MSB:137temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;138internal_state.spark_dwell_time_ms = temp_float;139offset++;140break;141case LOAD:142internal_state.engine_load_percent = data;143break;144case FUEL_PRESSURE_MSB:145// MS Fuel Pressure is unitless, store as KPA anyway146temp_float = (float)((data << 8) + read_byte_CRC32());147internal_state.fuel_pressure = temp_float;148offset++;149break;150151}152}153154// Read the four CRC bytes155uint32_t received_CRC;156received_CRC = port->read() << 24;157received_CRC += port->read() << 16;158received_CRC += port->read() << 8;159received_CRC += port->read();160161if (received_CRC != checksum) {162// hal.console->printf("EFI CRC: 0x%08x 0x%08x\n", received_CRC, checksum);163return false;164}165166// Calculate Fuel Consumption167// Duty Cycle (Percent, because that's how HFE gives us the calibration coefficients)168float duty_cycle = (internal_state.cylinder_status.injection_time_ms * internal_state.engine_speed_rpm)/600.0f;169uint32_t current_time = AP_HAL::millis();170// Super Simplified integration method - Error Analysis TBD171// This calculation gives erroneous results when the engine isn't running172if (internal_state.engine_speed_rpm > RPM_THRESHOLD) {173internal_state.fuel_consumption_rate_cm3pm = duty_cycle*get_coef1() - get_coef2();174internal_state.estimated_consumed_fuel_volume_cm3 += internal_state.fuel_consumption_rate_cm3pm * (current_time - internal_state.last_updated_ms)/60000.0f;175} else {176internal_state.fuel_consumption_rate_cm3pm = 0;177}178internal_state.last_updated_ms = current_time;179180return true;181182}183184void AP_EFI_Serial_MS::send_request(uint8_t table, uint16_t first_offset, uint16_t last_offset)185{186uint16_t length = last_offset - first_offset + 1;187// Fixed message size (0x0007)188// Command 'r' (0x72)189// Null CANid (0x00)190const uint8_t data[9] = {1910x00,1920x07,1930x72,1940x00,195(uint8_t)table,196(uint8_t)(first_offset >> 8),197(uint8_t)(first_offset),198(uint8_t)(length >> 8),199(uint8_t)(length)200};201202uint32_t crc = 0;203204// Write the request and calc CRC205for (uint8_t i = 0; i != sizeof(data) ; i++) {206// Message size is excluded from CRC207if (i > 1) {208crc = CRC32_compute_byte(crc, data[i]);209}210port->write(data[i]);211}212213// Write the CRC32214port->write((uint8_t)(crc >> 24));215port->write((uint8_t)(crc >> 16));216port->write((uint8_t)(crc >> 8));217port->write((uint8_t)crc);218219}220221uint8_t AP_EFI_Serial_MS::read_byte_CRC32()222{223// Read a byte and update the CRC224uint8_t data = port->read();225checksum = CRC32_compute_byte(checksum, data);226return data;227}228229// CRC32 matching MegaSquirt230uint32_t AP_EFI_Serial_MS::CRC32_compute_byte(uint32_t crc, uint8_t data)231{232crc ^= ~0U;233crc = crc_crc32(crc, &data, 1);234crc ^= ~0U;235return crc;236}237238#endif // AP_EFI_SERIAL_MS_ENABLED239240241