Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added AP_EFI_Serial_FH driver, changed AP_EFI and config to accommodate new driver #27313

Open
wants to merge 13 commits into
base: master
Choose a base branch
from

Conversation

gonzoveliki
Copy link

Dedicated serial driver for getting telemetry from EFI Fly Henry.
https://www.[flyhenry.cz/images/navody-pdf/engine-management/Engine_Management_Manual_260_Fly_henry1.pdf
It is still in development, I have to map and scale all readings thoroughly. It's not breaking anything... tested with CubeOrange+

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would strongly suggest using a much simpler parser for the packets, as outlined.


#if AP_EFI_SERIAL_FH_ENABLED

#include <AP_HAL/AP_HAL.h>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think anything's being used from this header.

Comment on lines +32 to +33
extern const AP_HAL::HAL &hal;

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
extern const AP_HAL::HAL &hal;

libraries/AP_EFI/AP_EFI_Serial_FH.cpp Outdated Show resolved Hide resolved
Comment on lines +40 to +48
// Indicate that temperature and fuel pressure are supported
internal_state.fuel_pressure_status = Fuel_Pressure_Status::OK;
internal_state.temperature_status = Temperature_Status::OK;

// FlyHenry ECU reports EGT
internal_state.cylinder_status.exhaust_gas_temperature = 0;
internal_state.cylinder_status.exhaust_gas_temperature2 = 0;

}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Initialise these in the header files where the variable is declared.

Do not initialise variables to zero unless they're on the stack (https://ardupilot.org/dev/docs/style-guide.html#implicit-zeroing-of-memory)

}


bool AP_EFI_Serial_FH::process(uint32_t const now) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
bool AP_EFI_Serial_FH::process(uint32_t const now) {
bool AP_EFI_Serial_FH::process(uint32_t const now)
{

You can use astyle to conform to the code style guides.

Comment on lines +52 to +57
uint8_t sum8(uint8_t *buf, size_t len) {
uint8_t sum = 0;
for (size_t i = 0; i < len; i++) sum += buf[i];
return sum;
}

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
uint8_t sum8(uint8_t *buf, size_t len) {
uint8_t sum = 0;
for (size_t i = 0; i < len; i++) sum += buf[i];
return sum;
}

available as crc_sum_of_bytes

Comment on lines +58 to +68
float convertFuelConsumption(float fuelConsumption_lph) {
const int // Conversion factors
litersToCubicCentimeters = 1000,// 1 liter = 1000 cm³
hoursToMinutes = 60; // 1 hour = 60 minutes

float // Convert l/h to cm³/m
fuelConsumption_cmh = fuelConsumption_lph * litersToCubicCentimeters,// l/h to cm³/h
fuelConsumption_cmm = fuelConsumption_cmh / hoursToMinutes; // cm³/h to cm³/m

return fuelConsumption_cmm;
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move this to the cpp file

uint8_t pkt[50];
};
size_t ind;
uint32_t last_recv; // ms
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
uint32_t last_recv; // ms

use last_recv_ms

@@ -32,6 +32,10 @@
#define AP_EFI_SCRIPTING_ENABLED (AP_EFI_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED)
#endif

#ifndef AP_EFI_SERIAL_FH_ENABLED
#define AP_EFI_SERIAL_FH_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
#define AP_EFI_SERIAL_FH_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED
#define AP_EFI_SERIAL_FH_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && AP_ICENGINE_ENABLED

@@ -73,7 +73,7 @@ class AP_ICEngine {

static AP_ICEngine *get_singleton() { return _singleton; }

private:
//!!private:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, no. This isn't acceptable.

If you think you can make a reasonable case for exposing the state machine state, make an accessor for it. Check other available interface lements first....

Copy link
Collaborator

@Hwurzburg Hwurzburg left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

needs build_options.py and extract_features.py

Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
@peterbarker
Copy link
Contributor

Ping @gonzoveliki this is awaiting rework.

@Hwurzburg
Copy link
Collaborator

@peterbarker aren't we doing LUA drivers instead of C++ drivers now for EFI?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants