From 49b7efe4cb9c80454ea869f9630e955e37652f89 Mon Sep 17 00:00:00 2001 From: Reilly Callaway Date: Wed, 30 Mar 2022 14:16:37 +1100 Subject: [PATCH] AP_EFI: Add currawong ECU EFI backend --- libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp | 72 +++++++++++++++++++++++ libraries/AP_EFI/AP_EFI_Currawong_ECU.h | 55 +++++++++++++++++ 2 files changed, 127 insertions(+) create mode 100644 libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp create mode 100644 libraries/AP_EFI/AP_EFI_Currawong_ECU.h diff --git a/libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp b/libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp new file mode 100644 index 0000000000..1cf2482b6f --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp @@ -0,0 +1,72 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * AP_EFI_Currawong_ECU.cpp + * + * Author: Reilly Callaway + */ + +#include +#include + +#if HAL_EFI_CURRAWONG_ECU_ENABLED + +extern const AP_HAL::HAL& hal; + +AP_EFI_Currawong_ECU* AP_EFI_Currawong_ECU::singleton; + +AP_EFI_Currawong_ECU::AP_EFI_Currawong_ECU(AP_EFI &_frontend) : + AP_EFI_Backend(_frontend) +{ + singleton = this; + + internal_state.oil_pressure_status = Oil_Pressure_Status::OIL_PRESSURE_STATUS_NOT_SUPPORTED; + internal_state.debris_status = Debris_Status::NOT_SUPPORTED; + internal_state.misfire_status = Misfire_Status::NOT_SUPPORTED; +} + +void AP_EFI_Currawong_ECU::update() +{ + // copy the data to the front end + copy_to_frontend(); +} + +bool AP_EFI_Currawong_ECU::handle_message(AP_HAL::CANFrame &frame) +{ + bool valid = true; + + // There are differences between Ardupilot EFI_State and types/scaling of Piccolo packets. + // So we first decode to Piccolo structs, and then store the data we need in EFI_State internal_state with any scaling required. + + // Structs to decode Piccolo messages into + ECU_TelemetryFast_t telemetryFast; + ECU_TelemetrySlow0_t telemetrySlow0; + ECU_TelemetrySlow1_t telemetrySlow1; + ECU_TelemetrySlow2_t telemetrySlow2; + ECU_Errors_t errors; + + // Throw the message at the decoding functions + + + if (valid) + { + internal_state.last_updated_ms = AP_HAL::millis(); + } + + return valid; +} + +#endif // HAL_EFI_CURRAWONG_ECU_ENABLED \ No newline at end of file diff --git a/libraries/AP_EFI/AP_EFI_Currawong_ECU.h b/libraries/AP_EFI/AP_EFI_Currawong_ECU.h new file mode 100644 index 0000000000..8692c100c8 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Currawong_ECU.h @@ -0,0 +1,55 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * AP_EFI_Currawong_ECU.h + * + * Author: Reilly Callaway + */ + +#pragma once + +#include "AP_EFI.h" +#include "AP_EFI_Backend.h" + +#ifndef HAL_EFI_CURRAWONG_ECU_ENABLED +#define HAL_EFI_CURRAWONG_ECU_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS && BOARD_FLASH_SIZE > 1024 +#endif + +#if HAL_EFI_CURRAWONG_ECU_ENABLED + + + +class AP_EFI_Currawong_ECU : public AP_EFI_Backend { +public: + AP_EFI_Currawong_ECU(AP_EFI &_frontend); + + void update() override; + + static AP_EFI_Currawong_ECU* get_instance(void) + { + return singleton; + } + +private: + bool handle_message(AP_HAL::CANFrame &frame); + + static AP_EFI_Currawong_ECU *singleton; + + friend class AP_PiccoloCAN; +}; + +#endif // HAL_EFI_NWPWU_ENABLED +