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_Hirth.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*/14151617#include "AP_EFI_config.h"1819#if AP_EFI_SERIAL_HIRTH_ENABLED20#include <AP_HAL/AP_HAL.h>21#include <AP_EFI/AP_EFI_Serial_Hirth.h>22#include <AP_SerialManager/AP_SerialManager.h>23#include <SRV_Channel/SRV_Channel.h>24#include <AP_ICEngine/AP_ICEngine.h>25#include <AP_Math/definitions.h>26#include <AP_Logger/AP_Logger.h>2728#define HIRTH_MAX_PKT_SIZE 10029#define HIRTH_MAX_RAW_PKT_SIZE 1033031#define SERIAL_WAIT_TIMEOUT_MS 1003233#define ENGINE_RUNNING 434#define THROTTLE_POSITION_FACTOR 1035#define INJECTION_TIME_RESOLUTION 0.836#define THROTTLE_POSITION_RESOLUTION 0.137#define VOLTAGE_RESOLUTION 0.0049 /* 5/1024 */38#define ADC_CALIBRATION (5.0/1024.0)39#define MAP_HPA_PER_VOLT_FACTOR 248.267340#define HPA_TO_KPA 0.141#define TPS_SCALE 0.704243// request/response status constants44#define QUANTITY_REQUEST_STATUS 0x0345#define QUANTITY_SET_VALUE 0x1746#define CODE_REQUEST_STATUS_1 0x0447#define CODE_REQUEST_STATUS_2 0x0B48#define CODE_REQUEST_STATUS_3 0x0D49#define CODE_SET_VALUE 0xC950#define CHECKSUM_REQUEST_STATUS_1 0xF951#define CHECKSUM_REQUEST_STATUS_2 0xF252#define CHECKSUM_REQUEST_STATUS_3 0xF053#define QUANTITY_RESPONSE_STATUS_1 0x5754#define QUANTITY_RESPONSE_STATUS_2 0x6555#define QUANTITY_RESPONSE_STATUS_3 0x6756#define QUANTITY_ACK_SET_VALUES 0x035758extern const AP_HAL::HAL& hal;5960/**61* @brief Constructor with port initialization62*63* @param _frontend64*/65AP_EFI_Serial_Hirth::AP_EFI_Serial_Hirth(AP_EFI &_frontend) :66AP_EFI_Backend(_frontend)67{68port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_EFI, 0);69set_default_coef1(1.0);70}7172/**73* @brief checks for response from or makes requests to Hirth ECU periodically74*75*/76void AP_EFI_Serial_Hirth::update()77{78if (port == nullptr) {79return;80}8182// parse response from Hirth83check_response();8485// send request86send_request();87}8889/**90* @brief Checks if required bytes are available and proceeds with parsing91*92*/93void AP_EFI_Serial_Hirth::check_response()94{95const uint32_t now = AP_HAL::millis();9697// waiting for response98if (!waiting_response) {99return;100}101102const uint32_t num_bytes = port->available();103104// if already requested105if (num_bytes >= expected_bytes) {106// read data from buffer107uint8_t computed_checksum = 0;108computed_checksum += res_data.quantity = port->read();109computed_checksum += res_data.code = port->read();110111if (res_data.code == requested_code) {112for (int i = 0; i < (res_data.quantity - QUANTITY_REQUEST_STATUS); i++) {113computed_checksum += raw_data[i] = port->read();114}115}116117res_data.checksum = port->read();118if (res_data.checksum != (256 - computed_checksum)) {119crc_fail_cnt++;120port->discard_input();121} else {122uptime = now - last_packet_ms;123last_packet_ms = now;124internal_state.last_updated_ms = now;125decode_data();126copy_to_frontend();127port->discard_input();128}129130waiting_response = false;131132#if HAL_LOGGING_ENABLED133log_status();134#endif135}136137// reset request if no response for SERIAL_WAIT_TIMEOUT_MS138if (waiting_response &&139now - last_request_ms > SERIAL_WAIT_TIMEOUT_MS) {140waiting_response = false;141last_request_ms = now;142143port->discard_input();144ack_fail_cnt++;145}146}147148/**149* @brief Send Throttle and Telemetry requests to Hirth150*151*/152void AP_EFI_Serial_Hirth::send_request()153{154if (waiting_response) {155return;156}157158const uint32_t now = AP_HAL::millis();159bool request_was_sent;160161// get new throttle value162const uint16_t new_throttle = (uint16_t)SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);163164// check for change or timeout for throttle value165if ((new_throttle != last_throttle) || (now - last_req_send_throttle_ms > 500)) {166// send new throttle value, only when ARMED167bool allow_throttle = hal.util->get_soft_armed();168if (!allow_throttle) {169#if AP_ICENGINE_ENABLED170const auto *ice = AP::ice();171if (ice != nullptr) {172allow_throttle = ice->allow_throttle_while_disarmed();173}174#endif // AP_ICENGINE_ENABLED175}176if (allow_throttle) {177request_was_sent = send_target_values(new_throttle);178} else {179request_was_sent = send_target_values(0);180}181182last_throttle = new_throttle;183last_req_send_throttle_ms = now;184} else {185// request Status request at the driver update rate if no throttle commands186request_was_sent = send_request_status();187}188189if (request_was_sent) {190waiting_response = true;191last_request_ms = now;192}193}194195196/**197* @brief sends the new throttle command to Hirth ECU198*199* @param thr - new throttle value given by SRV_Channel::k_throttle200* @return true - if success201* @return false - currently not implemented202*/203bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)204{205uint8_t computed_checksum = 0;206throttle_to_hirth = 0;207208// clear buffer209memset(raw_data, 0, ARRAY_SIZE(raw_data));210211#if AP_EFI_THROTTLE_LINEARISATION_ENABLED212// linearise throttle input213thr = linearise_throttle(thr);214#endif215216throttle_to_hirth = thr * THROTTLE_POSITION_FACTOR;217218uint8_t idx = 0;219220// set Quantity + Code + "20 bytes of records to set" + Checksum221computed_checksum += raw_data[idx++] = QUANTITY_SET_VALUE;222computed_checksum += raw_data[idx++] = requested_code = CODE_SET_VALUE;223computed_checksum += raw_data[idx++] = throttle_to_hirth & 0xFF;224computed_checksum += raw_data[idx++] = (throttle_to_hirth >> 8) & 0xFF;225226// checksum calculation227raw_data[QUANTITY_SET_VALUE - 1] = (256 - computed_checksum);228229expected_bytes = QUANTITY_ACK_SET_VALUES;230// write data231port->write(raw_data, QUANTITY_SET_VALUE);232233return true;234}235236237/**238* @brief cyclically sends different Status requests to Hirth ECU239*240* @return true - when successful241* @return false - not implemented242*/243bool AP_EFI_Serial_Hirth::send_request_status() {244245uint8_t requested_quantity;246uint8_t requested_checksum;247248switch (requested_code)249{250case CODE_REQUEST_STATUS_1:251requested_quantity = QUANTITY_REQUEST_STATUS;252requested_code = CODE_REQUEST_STATUS_2;253requested_checksum = CHECKSUM_REQUEST_STATUS_2;254expected_bytes = QUANTITY_RESPONSE_STATUS_2;255break;256case CODE_REQUEST_STATUS_2:257requested_quantity = QUANTITY_REQUEST_STATUS;258requested_code = CODE_REQUEST_STATUS_3;259requested_checksum = CHECKSUM_REQUEST_STATUS_3;260expected_bytes = QUANTITY_RESPONSE_STATUS_3;261break;262case CODE_REQUEST_STATUS_3:263requested_quantity = QUANTITY_REQUEST_STATUS;264requested_code = CODE_REQUEST_STATUS_1;265requested_checksum = CHECKSUM_REQUEST_STATUS_1;266expected_bytes = QUANTITY_RESPONSE_STATUS_1;267break;268default:269requested_quantity = QUANTITY_REQUEST_STATUS;270requested_code = CODE_REQUEST_STATUS_1;271requested_checksum = CHECKSUM_REQUEST_STATUS_1;272expected_bytes = QUANTITY_RESPONSE_STATUS_1;273break;274}275raw_data[0] = requested_quantity;276raw_data[1] = requested_code;277raw_data[2] = requested_checksum;278279port->write(raw_data, QUANTITY_REQUEST_STATUS);280281return true;282}283284285/**286* @brief parses the response from Hirth ECU and updates the internal state instance287*288*/289void AP_EFI_Serial_Hirth::decode_data()290{291const uint32_t now = AP_HAL::millis();292293switch (res_data.code) {294case CODE_REQUEST_STATUS_1: {295struct Record1 *record1 = (Record1*)raw_data;296297internal_state.engine_speed_rpm = record1->rpm;298internal_state.throttle_out = record1->throttle;299300// EFI2 log301internal_state.engine_state = (Engine_State)record1->engine_status;302303// ECYL log304internal_state.cylinder_status.injection_time_ms = record1->injection_time * INJECTION_TIME_RESOLUTION;305internal_state.cylinder_status.ignition_timing_deg = record1->ignition_angle;306307// EFI3 log308internal_state.ignition_voltage = record1->battery_voltage * VOLTAGE_RESOLUTION;309310sensor_status = record1->sensor_ok;311312// resusing mavlink variables as required for Hirth313// add in ADC voltage of MAP sensor > convert to MAP in kPa314internal_state.intake_manifold_pressure_kpa = record1->voltage_int_air_pressure * (ADC_CALIBRATION * MAP_HPA_PER_VOLT_FACTOR * HPA_TO_KPA);315internal_state.intake_manifold_temperature = C_TO_KELVIN(record1->air_temperature);316break;317}318319case CODE_REQUEST_STATUS_2: {320struct Record2 *record2 = (Record2*)raw_data;321322// EFI log323const float fuel_consumption_rate_lph = record2->fuel_consumption * 0.1;324325internal_state.fuel_consumption_rate_cm3pm = (fuel_consumption_rate_lph * 1000.0 / 60.0) * get_coef1();326327if (last_fuel_integration_ms != 0) {328// estimated_consumed_fuel_volume_cm3 is in cm3/pm329const float dt_minutes = (now - last_fuel_integration_ms)*(0.001/60);330internal_state.estimated_consumed_fuel_volume_cm3 += internal_state.fuel_consumption_rate_cm3pm * dt_minutes;331}332last_fuel_integration_ms = now;333334internal_state.throttle_position_percent = record2->throttle_percent_times_10 * 0.1;335break;336}337338case CODE_REQUEST_STATUS_3: {339struct Record3 *record3 = (Record3*)raw_data;340341// EFI3 Log342error_excess_temperature = record3->error_excess_temperature_bitfield;343344// ECYL log345internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(record3->excess_temperature_1);346internal_state.cylinder_status.cylinder_head_temperature2 = C_TO_KELVIN(record3->excess_temperature_2);347internal_state.cylinder_status.exhaust_gas_temperature = C_TO_KELVIN(record3->excess_temperature_3);348internal_state.cylinder_status.exhaust_gas_temperature2 = C_TO_KELVIN(record3->excess_temperature_4);349break;350}351352// case CODE_SET_VALUE:353// // Do nothing for now354// break;355}356}357358#if HAL_LOGGING_ENABLED359void AP_EFI_Serial_Hirth::log_status(void)360{361// @LoggerMessage: EFIS362// @Description: Electronic Fuel Injection data - Hirth specific Status information363// @Field: TimeUS: Time since system startup364// @Field: EET: Error Excess Temperature Bitfield365// @FieldBitmaskEnum: EET: AP_EFI_Serial_Hirth:::Error_Excess_Temp_Bitfield366// @Field: FLAG: Sensor Status Bitfield367// @FieldBitmaskEnum: FLAG: AP_EFI_Serial_Hirth:::Sensor_Status_Bitfield368// @Field: CRF: CRC failure count369// @Field: AKF: ACK failure count370// @Field: Up: Uptime between 2 messages371// @Field: ThO: Throttle output as received by the engine372// @Field: ThM: Modified throttle_to_hirth output sent to the engine373AP::logger().WriteStreaming("EFIS",374"TimeUS,EET,FLAG,CRF,AKF,Up,ThO,ThM",375"s-------",376"F-------",377"QHBIIIfH",378AP_HAL::micros64(),379uint16_t(error_excess_temperature),380uint8_t(sensor_status),381uint32_t(crc_fail_cnt),382uint32_t(ack_fail_cnt),383uint32_t(uptime),384float(internal_state.throttle_out),385uint16_t(throttle_to_hirth));386}387#endif // HAL_LOGGING_ENABLED388389#endif // AP_EFI_SERIAL_HIRTH_ENABLED390391392