AP_EFI: add defines for Lutan and MegaSquirt

This commit is contained in:
Peter Barker 2023-03-16 10:09:13 +11:00 committed by Peter Barker
parent 615f36f8a0
commit 1cd3e7327d
6 changed files with 42 additions and 13 deletions

View File

@ -87,12 +87,16 @@ void AP_EFI::init(void)
switch ((Type)type.get()) { switch ((Type)type.get()) {
case Type::NONE: case Type::NONE:
break; break;
#if AP_EFI_SERIAL_MS_ENABLED
case Type::MegaSquirt: case Type::MegaSquirt:
backend = new AP_EFI_Serial_MS(*this); backend = new AP_EFI_Serial_MS(*this);
break; break;
#endif
#if AP_EFI_SERIAL_LUTAN_ENABLED
case Type::Lutan: case Type::Lutan:
backend = new AP_EFI_Serial_Lutan(*this); backend = new AP_EFI_Serial_Lutan(*this);
break; break;
#endif
case Type::NWPMU: case Type::NWPMU:
#if AP_EFI_NWPWU_ENABLED #if AP_EFI_NWPWU_ENABLED
backend = new AP_EFI_NWPMU(*this); backend = new AP_EFI_NWPMU(*this);

View File

@ -12,18 +12,20 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_EFI_config.h"
#if AP_EFI_SERIAL_LUTAN_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_EFI_Serial_Lutan.h"
#include <AP_HAL/utility/sparse-endian.h> #include <AP_HAL/utility/sparse-endian.h>
#if HAL_EFI_ENABLED
#include <stdio.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_SerialManager/AP_SerialManager.h> #include <AP_SerialManager/AP_SerialManager.h>
#include "AP_EFI_Serial_Lutan.h"
#include <stdio.h>
// RPM Threshold for fuel consumption estimator // RPM Threshold for fuel consumption estimator
#define RPM_THRESHOLD 100 #define RPM_THRESHOLD 100
@ -107,4 +109,4 @@ void AP_EFI_Serial_Lutan::send_request(void)
port->write((const uint8_t *)&crc2, sizeof(crc2)); port->write((const uint8_t *)&crc2, sizeof(crc2));
} }
#endif // HAL_EFI_ENABLED #endif // AP_EFI_SERIAL_LUTAN_ENABLED

View File

@ -17,6 +17,10 @@
*/ */
#pragma once #pragma once
#include "AP_EFI_config.h"
#if AP_EFI_SERIAL_LUTAN_ENABLED
#include "AP_EFI.h" #include "AP_EFI.h"
#include "AP_EFI_Backend.h" #include "AP_EFI_Backend.h"
@ -81,3 +85,5 @@ private:
uint32_t last_request_ms; uint32_t last_request_ms;
uint32_t last_recv_ms; uint32_t last_recv_ms;
}; };
#endif // AP_EFI_SERIAL_LUTAN_ENABLED

View File

@ -12,14 +12,17 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <AP_HAL/AP_HAL.h>
#include "AP_EFI_Serial_MS.h"
#if HAL_EFI_ENABLED #include "AP_EFI_config.h"
#if AP_EFI_SERIAL_MS_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_SerialManager/AP_SerialManager.h> #include <AP_SerialManager/AP_SerialManager.h>
#include "AP_EFI_Serial_MS.h"
extern const AP_HAL::HAL &hal; extern const AP_HAL::HAL &hal;
AP_EFI_Serial_MS::AP_EFI_Serial_MS(AP_EFI &_frontend): AP_EFI_Serial_MS::AP_EFI_Serial_MS(AP_EFI &_frontend):
@ -230,4 +233,4 @@ uint32_t AP_EFI_Serial_MS::CRC32_compute_byte(uint32_t crc, uint8_t data)
return crc; return crc;
} }
#endif // HAL_EFI_ENABLED #endif // AP_EFI_SERIAL_MS_ENABLED

View File

@ -14,6 +14,10 @@
*/ */
#pragma once #pragma once
#include "AP_EFI_config.h"
#if AP_EFI_SERIAL_MS_ENABLED
#include "AP_EFI.h" #include "AP_EFI.h"
#include "AP_EFI_Backend.h" #include "AP_EFI_Backend.h"
@ -108,3 +112,5 @@ private:
RT_LAST_OFFSET = FUEL_PRESSURE_LSB RT_LAST_OFFSET = FUEL_PRESSURE_LSB
}; };
}; };
#endif // AP_EFI_SERIAL_MS_ENABLED

View File

@ -26,3 +26,11 @@
#ifndef AP_EFI_SCRIPTING_ENABLED #ifndef AP_EFI_SCRIPTING_ENABLED
#define AP_EFI_SCRIPTING_ENABLED (AP_EFI_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED) #define AP_EFI_SCRIPTING_ENABLED (AP_EFI_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED)
#endif #endif
#ifndef AP_EFI_SERIAL_MS_ENABLED
#define AP_EFI_SERIAL_MS_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_EFI_SERIAL_LUTAN_ENABLED
#define AP_EFI_SERIAL_LUTAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED
#endif