ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.h

1243 lines
50 KiB
C

// ECUPackets.h was generated by ProtoGen version 3.2.a
/*
* This file 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 file 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 <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ECUPACKETS_H
#define _ECUPACKETS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ECUProtocol.h"
#include "ECUDefines.h"
#include "ECUSettings.h"
/*!
* The throttle command packet sets the throttle position setpoint. The ECU
* will adjust the throttle position based on this command.
*/
typedef struct
{
float throttleCommand; //!< Commanded throttle position in percent
}ECU_ThrottleCommand_t;
//! Create the ECU_ThrottleCommand packet from parameters
void encodeECU_ThrottleCommandPacket(void* pkt, float throttleCommand);
//! Decode the ECU_ThrottleCommand packet to parameters
int decodeECU_ThrottleCommandPacket(const void* pkt, float* throttleCommand);
//! return the packet ID for the ECU_ThrottleCommand packet
#define getECU_ThrottleCommandPacketID() (PKT_ECU_THROTTLE)
//! return the minimum encoded length for the ECU_ThrottleCommand packet
#define getECU_ThrottleCommandMinDataLength() (2)
//! return the maximum encoded length for the ECU_ThrottleCommand packet
#define getECU_ThrottleCommandMaxDataLength() (2)
/*!
* The RPM command is used to send a target to the RPM governor on the ECU.
* Based on this command, the ECU will use a feedback loop to maintain the
* commanded engine speed by adjusting the throttle servo accordingly. If a
* valid RPM command is received by the ECU, it will automatically enter RPM
* control mode, and adjust the throttle position to match the desired RPM.
* Sending a throttle command will cause the ECU to stop the RPM loop and enter
* open-loop throttle control mode.
*/
typedef struct
{
uint16_t rpmCmd; //!< Engine speed command in revolutions per minute
uint8_t rpmCmdHigh; //!< RPM command in units of 50 RPM
uint8_t rpmCmdLow; //!< Low part of RPM command from 0 to 49
}ECU_RPMCommand_t;
//! Create the ECU_RPMCommand packet
void encodeECU_RPMCommandPacketStructure(void* pkt, const ECU_RPMCommand_t* user);
//! Decode the ECU_RPMCommand packet
int decodeECU_RPMCommandPacketStructure(const void* pkt, ECU_RPMCommand_t* user);
//! return the packet ID for the ECU_RPMCommand packet
#define getECU_RPMCommandPacketID() (PKT_ECU_RPM_COMMAND)
//! return the minimum encoded length for the ECU_RPMCommand packet
#define getECU_RPMCommandMinDataLength() (2)
//! return the maximum encoded length for the ECU_RPMCommand packet
#define getECU_RPMCommandMaxDataLength() (2)
typedef struct
{
bool driverPin8; //!< 1 if driver 8 is on
bool driverPin7; //!< 1 if driver 7 is on
bool driverPin2; //!< 1 if driver 2 is on
bool driverPin1; //!< 1 if driver 1 is on
bool throttleCurveOn; //!< 1 if the throttle curve is on.
bool rs232mode; //!< 1 if autronic, else auxiliary.
bool errorIndicator; //!< 1 if any errors are set - refer to [error packet](#PKT_ECU_ERROR_MSG)
bool enabled; //!< Global enable based on physical input
}ECU_ecuStatusBits_t;
/*!
* Fast telemetry contains high priority telemetry data and is transmitted at a
* user configurable period between 50ms (20Hz) and 10s. By default, the fast
* telemetry message is transmitted at 10Hz (every 100ms)
*/
typedef struct
{
float throttle; //!< Throttle signal (0 to 100%)
uint16_t rpm; //!< Engine speed in revolutions per minute
uint32_t fuelUsed; //!< Fuel used in grams
ECU_ecuStatusBits_t ecuStatusBits;
}ECU_TelemetryFast_t;
//! Encode a ECU_ecuStatusBits_t into a byte array
void encodeECU_ecuStatusBits_t(uint8_t* data, int* bytecount, const ECU_ecuStatusBits_t* user);
//! Decode a ECU_ecuStatusBits_t from a byte array
int decodeECU_ecuStatusBits_t(const uint8_t* data, int* bytecount, ECU_ecuStatusBits_t* user);
//! Create the ECU_TelemetryFast packet
void encodeECU_TelemetryFastPacketStructure(void* pkt, const ECU_TelemetryFast_t* user);
//! Decode the ECU_TelemetryFast packet
int decodeECU_TelemetryFastPacketStructure(const void* pkt, ECU_TelemetryFast_t* user);
//! Create the ECU_TelemetryFast packet from parameters
void encodeECU_TelemetryFastPacket(void* pkt, float throttle, uint16_t rpm, uint32_t fuelUsed, const ECU_ecuStatusBits_t* ecuStatusBits);
//! Decode the ECU_TelemetryFast packet to parameters
int decodeECU_TelemetryFastPacket(const void* pkt, float* throttle, uint16_t* rpm, uint32_t* fuelUsed, ECU_ecuStatusBits_t* ecuStatusBits);
//! return the packet ID for the ECU_TelemetryFast packet
#define getECU_TelemetryFastPacketID() (PKT_ECU_TELEMETRY_FAST)
//! return the minimum encoded length for the ECU_TelemetryFast packet
#define getECU_TelemetryFastMinDataLength() (8)
//! return the maximum encoded length for the ECU_TelemetryFast packet
#define getECU_TelemetryFastMaxDataLength() (8)
/*!
* This is the first of three slower telemetry packets which are transmitted by
* the ECU at a user customizable period (between 0.5s and 10.0s). These three
* packets contain data that is not likely to change as quickly as the data in
* the fast telemetry packet. By default, the slow telemetry messages are
* transmitted at 1Hz (period of 1.0s).
*/
typedef struct
{
uint16_t rpmCmd; //!< The reconstructed RPM command
float map; //!< The reconstructed manifold pressure in kilo-Pascals
ECUThrottleSource throttleSrc; //!< Source of the throttle information
uint16_t throttlePulse; //!< Throttle pulse width in microseconds
float cht; //!< Cylinder head temperature in Celsius
float baro; //!< Barometric pressure in kilo-Pascals
}ECU_TelemetrySlow0_t;
//! Create the ECU_TelemetrySlow0 packet
void encodeECU_TelemetrySlow0PacketStructure(void* pkt, const ECU_TelemetrySlow0_t* user);
//! Decode the ECU_TelemetrySlow0 packet
int decodeECU_TelemetrySlow0PacketStructure(const void* pkt, ECU_TelemetrySlow0_t* user);
//! return the packet ID for the ECU_TelemetrySlow0 packet
#define getECU_TelemetrySlow0PacketID() (PKT_ECU_TELEMETRY_SLOW_0)
//! return the minimum encoded length for the ECU_TelemetrySlow0 packet
#define getECU_TelemetrySlow0MinDataLength() (8)
//! return the maximum encoded length for the ECU_TelemetrySlow0 packet
#define getECU_TelemetrySlow0MaxDataLength() (8)
/*!
* ECU RPM governor mode enumeration
*/
typedef enum
{
ECU_GOV_MODE_NONE, //!< RPM governor is off
ECU_GOV_MODE_THROTTLE,//!< RPM governer setpoint is based on throttle input
ECU_GOV_MODE_DIRECT //!< RPM governor setpoint comes from direct command
} ECUGovernorMode;
/*!
* The second of three slow telemetry packets
*/
typedef struct
{
float mat; //!< Inlet air temperature in Celsius
float fuelPressure; //!< Fuel pressure in kilo-Pascals
uint32_t hobbs; //!< Engine run time in seconds.
float voltage; //!< Input voltage in Volts
ECUGovernorMode governorMode; //!< Operational mode of the governor
}ECU_TelemetrySlow1_t;
//! Create the ECU_TelemetrySlow1 packet
void encodeECU_TelemetrySlow1PacketStructure(void* pkt, const ECU_TelemetrySlow1_t* user);
//! Decode the ECU_TelemetrySlow1 packet
int decodeECU_TelemetrySlow1PacketStructure(const void* pkt, ECU_TelemetrySlow1_t* user);
//! return the packet ID for the ECU_TelemetrySlow1 packet
#define getECU_TelemetrySlow1PacketID() (PKT_ECU_TELEMETRY_SLOW_1)
//! return the minimum encoded length for the ECU_TelemetrySlow1 packet
#define getECU_TelemetrySlow1MinDataLength() (8)
//! return the maximum encoded length for the ECU_TelemetrySlow1 packet
#define getECU_TelemetrySlow1MaxDataLength() (8)
/*!
* The third of three slow telemetry packets
*/
typedef struct
{
float cpuLoad; //!< CPU load in percent
float chargeTemp; //!< Charge temperature in Celsius
float injectorDuty; //!< Injector duty cycle in percent
float ignAngle1; //!< First ignition advance angle in degrees
float ignAngle2; //!< Second ignition advance angle in degrees
float flowRate; //!< Fuel flow rate in grams per minute
}ECU_TelemetrySlow2_t;
//! Create the ECU_TelemetrySlow2 packet
void encodeECU_TelemetrySlow2PacketStructure(void* pkt, const ECU_TelemetrySlow2_t* user);
//! Decode the ECU_TelemetrySlow2 packet
int decodeECU_TelemetrySlow2PacketStructure(const void* pkt, ECU_TelemetrySlow2_t* user);
//! return the packet ID for the ECU_TelemetrySlow2 packet
#define getECU_TelemetrySlow2PacketID() (PKT_ECU_TELEMETRY_SLOW_2)
//! return the minimum encoded length for the ECU_TelemetrySlow2 packet
#define getECU_TelemetrySlow2MinDataLength() (8)
//! return the maximum encoded length for the ECU_TelemetrySlow2 packet
#define getECU_TelemetrySlow2MaxDataLength() (8)
/*!
* Enumeration of auxiliary to autronic serial relay states. Autronic relay is
* an advanced feature used to allow simultaneous connection of the Autronic
* ECUCal software and the auxiliary processor. Autronic relay should only be
* needed for engine development.
*/
typedef enum
{
AUT_RELAY_OFF, //!< Relay is disengaged, 19200 autronic interface rate; must use calibration switch to connect to Autronic
AUT_RELAY_PENDING,//!< Relay enabled but not detected, 19200 autronic and external serial interface rate
AUT_RELAY_ON //!< Relay detected, 38400 autronic and external serial interface rate
} ECUAutronicRelayState;
/*!
* The hardware config packet contains the ECU serial number and various ECU
* configuration data. Send a zero length packet to request this data.
*/
typedef struct
{
uint16_t serialNumber; //!< ECU serial number
uint16_t fuelDivisor; //!< Fuel used divisior. If the divisor is greater than 100 then it is interpreted as units of 0.01 (for a higher resolution fuel calibration)
ECUAutronicRelayState relayState; //!< Autronic relay state. This is a volatile status which will reset to AUT_RELAY_OFF on ECU power cycle.
bool resetFuelUsedOnStart; //!< Set if the fuel used value is reset each on each ECU power cycle
}ECU_HardwareConfig_t;
//! Create the ECU_HardwareConfig packet
void encodeECU_HardwareConfigPacketStructure(void* pkt, const ECU_HardwareConfig_t* user);
//! Decode the ECU_HardwareConfig packet
int decodeECU_HardwareConfigPacketStructure(const void* pkt, ECU_HardwareConfig_t* user);
//! return the packet ID for the ECU_HardwareConfig packet
#define getECU_HardwareConfigPacketID() (PKT_ECU_HARDWARE_CONFIG)
//! return the minimum encoded length for the ECU_HardwareConfig packet
#define getECU_HardwareConfigMinDataLength() (5)
//! return the maximum encoded length for the ECU_HardwareConfig packet
#define getECU_HardwareConfigMaxDataLength() (5)
/*!
* The software version packet contains the auxiliary processor firmware
* version information. Send a zero length packet to request this data.
*/
typedef struct
{
bool release; //!< 1 = Release version, 0 = Testing version
unsigned versionMajor : 6; //!< Major version number
uint8_t versionMinor; //!< Minor version number
uint8_t versionRev; //!< Revision number
uint8_t month; //!< The release month from 1 (January) to 12 (December)
uint8_t day; //!< The release day of month from 1 to 31
uint16_t year; //!< The release year
uint16_t checksum; //!< Firmware checksum
}ECU_Version_t;
//! Create the ECU_Version packet
void encodeECU_VersionPacketStructure(void* pkt, const ECU_Version_t* user);
//! Decode the ECU_Version packet
int decodeECU_VersionPacketStructure(const void* pkt, ECU_Version_t* user);
//! return the packet ID for the ECU_Version packet
#define getECU_VersionPacketID() (PKT_ECU_SOFTWARE_VERSION)
//! return the minimum encoded length for the ECU_Version packet
#define getECU_VersionMinDataLength() (8)
//! return the maximum encoded length for the ECU_Version packet
#define getECU_VersionMaxDataLength() (8)
/*!
* The errors packet contains error status information for the ECU. If any
* error bits are set, then the global error bit in the [fast
* telemetry](#PKT_ECU_TELEMETRY_FAST) packet will also be set. Send a zero
* length packet to request this data.
*/
typedef struct
{
ECU_AutronicErrorBits_t autronicErrors; //!< Error bits for the Autronic processor
ECU_AuxiliaryErrorBits_t auxiliaryErrors; //!< Error bits for the auxiliary processor
}ECU_Errors_t;
//! Create the ECU_Errors packet
void encodeECU_ErrorsPacketStructure(void* pkt, const ECU_Errors_t* user);
//! Decode the ECU_Errors packet
int decodeECU_ErrorsPacketStructure(const void* pkt, ECU_Errors_t* user);
//! return the packet ID for the ECU_Errors packet
#define getECU_ErrorsPacketID() (PKT_ECU_ERROR_MSG)
//! return the minimum encoded length for the ECU_Errors packet
#define getECU_ErrorsMinDataLength() (8)
//! return the maximum encoded length for the ECU_Errors packet
#define getECU_ErrorsMaxDataLength() (8)
/*!
* The power cycles packet contains information on the reset condition of the
* ECU. Send a zero length packet to request this data.
*/
typedef struct
{
uint16_t powerCycles; //!< Number of power cycles
uint8_t reserved;
uint8_t resetCode; //!< Auxiliary processor reset code
uint32_t systemTime; //!< Milliseconds since system reset
}ECU_PowerCycles_t;
//! Create the ECU_PowerCycles packet
void encodeECU_PowerCyclesPacketStructure(void* pkt, const ECU_PowerCycles_t* user);
//! Decode the ECU_PowerCycles packet
int decodeECU_PowerCyclesPacketStructure(const void* pkt, ECU_PowerCycles_t* user);
//! return the packet ID for the ECU_PowerCycles packet
#define getECU_PowerCyclesPacketID() (PKT_ECU_POWER_CYCLES)
//! return the minimum encoded length for the ECU_PowerCycles packet
#define getECU_PowerCyclesMinDataLength() (8)
//! return the maximum encoded length for the ECU_PowerCycles packet
#define getECU_PowerCyclesMaxDataLength() (8)
/*!
* The fuel pump debug packet contains information on the pump control system.
* Send a zero length packet to request this data.
*/
typedef struct
{
float pTerm; //!< Proportional term of the pump feedback control in percent
float iTerm; //!< Integral term of the pump feedback control in percent
float dutyCycle; //!< Pump duty cycle in percent
float fuelPressure; //!< Fuel pressure in kilo-Pascals
}ECU_PumpDebug_t;
//! Create the ECU_PumpDebug packet
void encodeECU_PumpDebugPacketStructure(void* pkt, const ECU_PumpDebug_t* user);
//! Decode the ECU_PumpDebug packet
int decodeECU_PumpDebugPacketStructure(const void* pkt, ECU_PumpDebug_t* user);
//! return the packet ID for the ECU_PumpDebug packet
#define getECU_PumpDebugPacketID() (PKT_ECU_PUMP_DEBUG)
//! return the minimum encoded length for the ECU_PumpDebug packet
#define getECU_PumpDebugMinDataLength() (8)
//! return the maximum encoded length for the ECU_PumpDebug packet
#define getECU_PumpDebugMaxDataLength() (8)
/*!
* While the engine time contained in the ECU telemetry packet can be reset by
* the user, the ECU also stores the total engine time, which cannot be reset
* by the user. Send a zero length packet to request this data.
*/
typedef struct
{
uint32_t hobbs; //!< Total engine run time in seconds
}ECU_TotalEngineTime_t;
//! Create the ECU_TotalEngineTime packet from parameters
void encodeECU_TotalEngineTimePacket(void* pkt, uint32_t hobbs);
//! Decode the ECU_TotalEngineTime packet to parameters
int decodeECU_TotalEngineTimePacket(const void* pkt, uint32_t* hobbs);
//! return the packet ID for the ECU_TotalEngineTime packet
#define getECU_TotalEngineTimePacketID() (PKT_ECU_TOTAL_ENGINE_TIME)
//! return the minimum encoded length for the ECU_TotalEngineTime packet
#define getECU_TotalEngineTimeMinDataLength() (3)
//! return the maximum encoded length for the ECU_TotalEngineTime packet
#define getECU_TotalEngineTimeMaxDataLength() (3)
/*!
* The eeprom settings packet contains information on the non-volatile ECU
* settings stored in eeprom. In particular, it provides a checksum of the
* settings data for easy comparison of settings between different ECUs. Send a
* zero length packet to request this data.
*/
typedef struct
{
uint8_t eepromVersion; //!< Version of the EEPROM data
uint16_t eepromSize; //!< Number of bytes of the EEPROM data
uint16_t eepromChecksum; //!< Fletcher's checksum of the EEPROM data
ECU_CompileOptions_t compileOptions; //!< ECU compilation options
}ECU_eepromSettings_t;
//! Create the ECU_eepromSettings packet
void encodeECU_eepromSettingsPacketStructure(void* pkt, const ECU_eepromSettings_t* user);
//! Decode the ECU_eepromSettings packet
int decodeECU_eepromSettingsPacketStructure(const void* pkt, ECU_eepromSettings_t* user);
//! Create the ECU_eepromSettings packet from parameters
void encodeECU_eepromSettingsPacket(void* pkt, uint8_t eepromVersion, uint16_t eepromSize, uint16_t eepromChecksum, const ECU_CompileOptions_t* compileOptions);
//! Decode the ECU_eepromSettings packet to parameters
int decodeECU_eepromSettingsPacket(const void* pkt, uint8_t* eepromVersion, uint16_t* eepromSize, uint16_t* eepromChecksum, ECU_CompileOptions_t* compileOptions);
//! return the packet ID for the ECU_eepromSettings packet
#define getECU_eepromSettingsPacketID() (PKT_ECU_SETTINGS_DATA)
//! return the minimum encoded length for the ECU_eepromSettings packet
#define getECU_eepromSettingsMinDataLength() (7)
//! return the maximum encoded length for the ECU_eepromSettings packet
#define getECU_eepromSettingsMaxDataLength() (7)
/*!
* Control loop settings for the CHT control loop
*/
typedef struct
{
uint8_t dTermFilter; //!< Filter value for derivative term
bool enabled; //!< CHT control loop enabled
uint8_t targetTemp; //!< Target CHT temperature
float Kp; //!< Proportaional gain Kp
float Ki; //!< Proportaional gain Ki
float Kd; //!< Proportaional gain Kd
}ECU_CHTLoopSettings_t;
//! Create the ECU_CHTLoopSettings packet
void encodeECU_CHTLoopSettingsPacketStructure(void* pkt, const ECU_CHTLoopSettings_t* user);
//! Decode the ECU_CHTLoopSettings packet
int decodeECU_CHTLoopSettingsPacketStructure(const void* pkt, ECU_CHTLoopSettings_t* user);
//! Create the ECU_CHTLoopSettings packet from parameters
void encodeECU_CHTLoopSettingsPacket(void* pkt, uint8_t dTermFilter, bool enabled, uint8_t targetTemp, float Kp, float Ki, float Kd);
//! Decode the ECU_CHTLoopSettings packet to parameters
int decodeECU_CHTLoopSettingsPacket(const void* pkt, uint8_t* dTermFilter, bool* enabled, uint8_t* targetTemp, float* Kp, float* Ki, float* Kd);
//! return the packet ID for the ECU_CHTLoopSettings packet
#define getECU_CHTLoopSettingsPacketID() (PKT_ECU_CHT_LOOP)
//! return the minimum encoded length for the ECU_CHTLoopSettings packet
#define getECU_CHTLoopSettingsMinDataLength() (8)
//! return the maximum encoded length for the ECU_CHTLoopSettings packet
#define getECU_CHTLoopSettingsMaxDataLength() (8)
/*!
* Dual pump control telemetry. Send a zero-length packet with this identifier
* to the ECU to poll (request) this packet.
*/
typedef struct
{
uint8_t mode; //!< Current pump mode (which pump is running). Refer to the DualFuelPumpMode enumeration.
uint8_t state; //!< Current pump state machine state. Refer to the DualFuelPumpState enumeration.
uint16_t stateTimer; //!< Time spent in current state
}ECU_DualPumpControlTelemetry_t;
//! Create the ECU_DualPumpControlTelemetry packet
void encodeECU_DualPumpControlTelemetryPacketStructure(void* pkt, const ECU_DualPumpControlTelemetry_t* user);
//! Decode the ECU_DualPumpControlTelemetry packet
int decodeECU_DualPumpControlTelemetryPacketStructure(const void* pkt, ECU_DualPumpControlTelemetry_t* user);
//! return the packet ID for the ECU_DualPumpControlTelemetry packet
#define getECU_DualPumpControlTelemetryPacketID() (0x08)
//! return the minimum encoded length for the ECU_DualPumpControlTelemetry packet
#define getECU_DualPumpControlTelemetryMinDataLength() (4)
//! return the maximum encoded length for the ECU_DualPumpControlTelemetry packet
#define getECU_DualPumpControlTelemetryMaxDataLength() (4)
/*!
* Set the telemetry period for dual-pump messages
*/
typedef struct
{
uint8_t period; //!< Telemetry period (0 = Off)
}ECU_DualPump_SetTelemetryPeriod_t;
//! Create the ECU_DualPump_SetTelemetryPeriod packet from parameters
void encodeECU_DualPump_SetTelemetryPeriodPacket(void* pkt, uint8_t period);
//! Decode the ECU_DualPump_SetTelemetryPeriod packet to parameters
int decodeECU_DualPump_SetTelemetryPeriodPacket(const void* pkt, uint8_t* period);
//! return the packet ID for the ECU_DualPump_SetTelemetryPeriod packet
#define getECU_DualPump_SetTelemetryPeriodPacketID() (0x08)
//! return the minimum encoded length for the ECU_DualPump_SetTelemetryPeriod packet
#define getECU_DualPump_SetTelemetryPeriodMinDataLength() (2)
//! return the maximum encoded length for the ECU_DualPump_SetTelemetryPeriod packet
#define getECU_DualPump_SetTelemetryPeriodMaxDataLength() (2)
/*!
* Command to manually select a given pump mode.
*/
typedef struct
{
uint8_t pump; //!< Pump selection (see DualFuelPumpMode enumeration)
}ECU_DualPump_SelectPump_t;
//! Create the ECU_DualPump_SelectPump packet from parameters
void encodeECU_DualPump_SelectPumpPacket(void* pkt, uint8_t pump);
//! Decode the ECU_DualPump_SelectPump packet to parameters
int decodeECU_DualPump_SelectPumpPacket(const void* pkt, uint8_t* pump);
//! return the packet ID for the ECU_DualPump_SelectPump packet
#define getECU_DualPump_SelectPumpPacketID() (0x08)
//! return the minimum encoded length for the ECU_DualPump_SelectPump packet
#define getECU_DualPump_SelectPumpMinDataLength() (3)
//! return the maximum encoded length for the ECU_DualPump_SelectPump packet
#define getECU_DualPump_SelectPumpMaxDataLength() (3)
/*!
* Command to temporarily run a particular pump in test mode. ECU will revert
* to OTHER pump when test expires
*/
typedef struct
{
uint8_t pump; //!< Pump selection (see DualFuelPumpMode enumeration)
uint8_t timeout; //!< Test timeout
}ECU_DualPump_TestPump_t;
//! Create the ECU_DualPump_TestPump packet
void encodeECU_DualPump_TestPumpPacketStructure(void* pkt, const ECU_DualPump_TestPump_t* user);
//! Decode the ECU_DualPump_TestPump packet
int decodeECU_DualPump_TestPumpPacketStructure(const void* pkt, ECU_DualPump_TestPump_t* user);
//! return the packet ID for the ECU_DualPump_TestPump packet
#define getECU_DualPump_TestPumpPacketID() (0x08)
//! return the minimum encoded length for the ECU_DualPump_TestPump packet
#define getECU_DualPump_TestPumpMinDataLength() (3)
//! return the maximum encoded length for the ECU_DualPump_TestPump packet
#define getECU_DualPump_TestPumpMaxDataLength() (4)
//! Create the ECU_ThrottleCalibration packet
void encodeECU_ThrottleCalibrationPacketStructure(void* pkt, const ECU_ThrottleSettings_t* user);
//! Decode the ECU_ThrottleCalibration packet
int decodeECU_ThrottleCalibrationPacketStructure(const void* pkt, ECU_ThrottleSettings_t* user);
//! Create the ECU_ThrottleCalibration packet from parameters
void encodeECU_ThrottleCalibrationPacket(void* pkt, uint16_t pulseClosed, uint16_t pulseOpen, const ECU_ThrottleConfigBits_t* config, uint16_t pulseInputClosed, uint16_t pulseInputOpen);
//! Decode the ECU_ThrottleCalibration packet to parameters
int decodeECU_ThrottleCalibrationPacket(const void* pkt, uint16_t* pulseClosed, uint16_t* pulseOpen, ECU_ThrottleConfigBits_t* config, uint16_t* pulseInputClosed, uint16_t* pulseInputOpen);
//! return the packet ID for the ECU_ThrottleCalibration packet
#define getECU_ThrottleCalibrationPacketID() (PKT_ECU_THROTTLE_CALIBRATION)
//! return the minimum encoded length for the ECU_ThrottleCalibration packet
#define getECU_ThrottleCalibrationMinDataLength() (8)
//! return the maximum encoded length for the ECU_ThrottleCalibration packet
#define getECU_ThrottleCalibrationMaxDataLength() (8)
//! Create the ECU_RPMLoopCalibration packet
void encodeECU_RPMLoopCalibrationPacketStructure(void* pkt, const ECU_GovernorSettings_t* user);
//! Decode the ECU_RPMLoopCalibration packet
int decodeECU_RPMLoopCalibrationPacketStructure(const void* pkt, ECU_GovernorSettings_t* user);
//! return the packet ID for the ECU_RPMLoopCalibration packet
#define getECU_RPMLoopCalibrationPacketID() (PKT_ECU_RPM_CALIBRATION)
//! return the minimum encoded length for the ECU_RPMLoopCalibration packet
#define getECU_RPMLoopCalibrationMinDataLength() (8)
//! return the maximum encoded length for the ECU_RPMLoopCalibration packet
#define getECU_RPMLoopCalibrationMaxDataLength() (8)
//! Create the ECU_TPSDelayCalibration packet
void encodeECU_TPSDelayCalibrationPacketStructure(void* pkt, const ECU_ThrottleSettings_t* user);
//! Decode the ECU_TPSDelayCalibration packet
int decodeECU_TPSDelayCalibrationPacketStructure(const void* pkt, ECU_ThrottleSettings_t* user);
//! Create the ECU_TPSDelayCalibration packet from parameters
void encodeECU_TPSDelayCalibrationPacket(void* pkt, uint8_t delay, const ECU_ThrottleDelayConfigBits_t* delayConfig, uint8_t maxDelay, uint8_t minDelay, uint8_t softLimit, uint8_t falloffRate, uint8_t throttleTarget, uint8_t hardLimit);
//! Decode the ECU_TPSDelayCalibration packet to parameters
int decodeECU_TPSDelayCalibrationPacket(const void* pkt, uint8_t* delay, ECU_ThrottleDelayConfigBits_t* delayConfig, uint8_t* maxDelay, uint8_t* minDelay, uint8_t* softLimit, uint8_t* falloffRate, uint8_t* throttleTarget, uint8_t* hardLimit);
//! return the packet ID for the ECU_TPSDelayCalibration packet
#define getECU_TPSDelayCalibrationPacketID() (PKT_ECU_TPS_DELAY_CONFIG)
//! return the minimum encoded length for the ECU_TPSDelayCalibration packet
#define getECU_TPSDelayCalibrationMinDataLength() (8)
//! return the maximum encoded length for the ECU_TPSDelayCalibration packet
#define getECU_TPSDelayCalibrationMaxDataLength() (8)
/*!
* The telmetry settings packet is used to configure the telemetry data rates
* for the ECU. The ECU will echo the packet as confirmation of its receipt.
* Send a zero length packet to request the current settings.
*/
typedef struct
{
uint8_t fastTelemetryPeriod; //!< Time between fast telemetry packets in 50ms increments
uint8_t slowTelemetryPeriod; //!< Time between slow telemetry packets in 500ms increments
uint8_t silencePeriod; //!< Seconds of time the ECU waits after bootup before sending telemetry.
}ECU_TelemetrySettings_t;
//! Create the ECU_TelemetrySettings packet
void encodeECU_TelemetrySettingsPacketStructure(void* pkt, const ECU_TelemetrySettings_t* user);
//! Decode the ECU_TelemetrySettings packet
int decodeECU_TelemetrySettingsPacketStructure(const void* pkt, ECU_TelemetrySettings_t* user);
//! return the packet ID for the ECU_TelemetrySettings packet
#define getECU_TelemetrySettingsPacketID() (PKT_ECU_TELEMETRY_SETTINGS)
//! return the minimum encoded length for the ECU_TelemetrySettings packet
#define getECU_TelemetrySettingsMinDataLength() (3)
//! return the maximum encoded length for the ECU_TelemetrySettings packet
#define getECU_TelemetrySettingsMaxDataLength() (3)
//! Create the ECU_PumpConfig packet
void encodeECU_PumpConfigPacketStructure(void* pkt, const ECU_PumpSettings_t* user);
//! Decode the ECU_PumpConfig packet
int decodeECU_PumpConfigPacketStructure(const void* pkt, ECU_PumpSettings_t* user);
//! return the packet ID for the ECU_PumpConfig packet
#define getECU_PumpConfigPacketID() (PKT_ECU_PUMP_CONFIG)
//! return the minimum encoded length for the ECU_PumpConfig packet
#define getECU_PumpConfigMinDataLength() (8)
//! return the maximum encoded length for the ECU_PumpConfig packet
#define getECU_PumpConfigMaxDataLength() (8)
//! Create the ECU_Pump2Config packet
void encodeECU_Pump2ConfigPacketStructure(void* pkt, const ECU_PumpSettings_t* user);
//! Decode the ECU_Pump2Config packet
int decodeECU_Pump2ConfigPacketStructure(const void* pkt, ECU_PumpSettings_t* user);
//! return the packet ID for the ECU_Pump2Config packet
#define getECU_Pump2ConfigPacketID() (PKT_ECU_PUMP_2_CONFIG)
//! return the minimum encoded length for the ECU_Pump2Config packet
#define getECU_Pump2ConfigMinDataLength() (7)
//! return the maximum encoded length for the ECU_Pump2Config packet
#define getECU_Pump2ConfigMaxDataLength() (7)
/*!
* The user data packet provides the user with 8 (eight) bytes of data for
* storing custom parameters or settings in ECU EEPROM (non-volatile) memory.
* The ECU does not make use of these values; they are simply for storing user
* data. Send a zero length packet to request the current settings. To set
* these values send the system command SET_USER_DATA. Data values must be set
* individually.
*/
typedef struct
{
uint8_t userData[8]; //!< 8 bytes of user data
}ECU_UserData_t;
//! Create the ECU_UserData packet from parameters
void encodeECU_UserDataPacket(void* pkt, const uint8_t userData[8]);
//! Decode the ECU_UserData packet to parameters
int decodeECU_UserDataPacket(const void* pkt, uint8_t userData[8]);
//! return the packet ID for the ECU_UserData packet
#define getECU_UserDataPacketID() (PKT_ECU_USER_DATA)
//! return the minimum encoded length for the ECU_UserData packet
#define getECU_UserDataMinDataLength() (8)
//! return the maximum encoded length for the ECU_UserData packet
#define getECU_UserDataMaxDataLength() (8)
/*!
* First throttle curve packet, which contains the lower 6 term of the throttle
* linearization table. To request the throttle curve data (both packets), send
* the system command REQUEST_THROTTLE_CURVE_DATA. To change the throttle curve
* data send the system command SET_THROTTLE_CURVE_ELEMENT.
*/
typedef struct
{
float throttleCurve[6]; //!< Throttle output values for the lower 6 cells in the throttle lookup table
}ECU_ThrottleCurve_t;
//! Create the ECU_ThrottleCurve packet from parameters
void encodeECU_ThrottleCurvePacket(void* pkt, const float throttleCurve[6]);
//! Decode the ECU_ThrottleCurve packet to parameters
int decodeECU_ThrottleCurvePacket(const void* pkt, float throttleCurve[6]);
//! return the packet ID for the ECU_ThrottleCurve packet
#define getECU_ThrottleCurvePacketID() (PKT_ECU_THROTTLE_CURVE_0)
//! return the minimum encoded length for the ECU_ThrottleCurve packet
#define getECU_ThrottleCurveMinDataLength() (6)
//! return the maximum encoded length for the ECU_ThrottleCurve packet
#define getECU_ThrottleCurveMaxDataLength() (6)
//! Create the ECU_ThrottleCurve1 packet from parameters
void encodeECU_ThrottleCurve1Packet(void* pkt, const float throttleCurve[5]);
//! Decode the ECU_ThrottleCurve1 packet to parameters
int decodeECU_ThrottleCurve1Packet(const void* pkt, float throttleCurve[5]);
//! return the packet ID for the ECU_ThrottleCurve1 packet
#define getECU_ThrottleCurve1PacketID() (PKT_ECU_THROTTLE_CURVE_1)
//! return the minimum encoded length for the ECU_ThrottleCurve1 packet
#define getECU_ThrottleCurve1MinDataLength() (5)
//! return the maximum encoded length for the ECU_ThrottleCurve1 packet
#define getECU_ThrottleCurve1MaxDataLength() (5)
/*!
* The system command packets follow the format provided below. Refer further
* in the document for complete documentation on each system command packet.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration
uint8_t parambytes[3]; //!< Up to 3 parameter bytes for a system command
}ECU_SystemCommand_t;
//! Create the ECU_SystemCommand packet
void encodeECU_SystemCommandPacketStructure(void* pkt, const ECU_SystemCommand_t* user);
//! Decode the ECU_SystemCommand packet
int decodeECU_SystemCommandPacketStructure(const void* pkt, ECU_SystemCommand_t* user);
//! return the packet ID for the ECU_SystemCommand packet
#define getECU_SystemCommandPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SystemCommand packet
#define getECU_SystemCommandMinDataLength() (1)
//! return the maximum encoded length for the ECU_SystemCommand packet
#define getECU_SystemCommandMaxDataLength() (4)
/*!
* Save the current value of the analog throttle position input as the 'Closed'
* position. To calibrate the closed analog input position, set the desired
* analog input level, and send this command to the ECU.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_CalibrateAnalogClosed_t;
//! Create the ECU_CalibrateAnalogClosed packet from parameters
void encodeECU_CalibrateAnalogClosedPacket(void* pkt);
//! Decode the ECU_CalibrateAnalogClosed packet to parameters
int decodeECU_CalibrateAnalogClosedPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_CalibrateAnalogClosed packet
#define getECU_CalibrateAnalogClosedPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_CalibrateAnalogClosed packet
#define getECU_CalibrateAnalogClosedMinDataLength() (1)
//! return the maximum encoded length for the ECU_CalibrateAnalogClosed packet
#define getECU_CalibrateAnalogClosedMaxDataLength() (1)
/*!
* Save the current value of the analog throttle position input as the 'Open'
* position. To calibrate the open analog input position, set the desired
* analog input level, and send this command to the ECU.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_CalibrateAnalogOpen_t;
//! Create the ECU_CalibrateAnalogOpen packet from parameters
void encodeECU_CalibrateAnalogOpenPacket(void* pkt);
//! Decode the ECU_CalibrateAnalogOpen packet to parameters
int decodeECU_CalibrateAnalogOpenPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_CalibrateAnalogOpen packet
#define getECU_CalibrateAnalogOpenPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_CalibrateAnalogOpen packet
#define getECU_CalibrateAnalogOpenMinDataLength() (1)
//! return the maximum encoded length for the ECU_CalibrateAnalogOpen packet
#define getECU_CalibrateAnalogOpenMaxDataLength() (1)
/*!
* Save the current value of the throttle output pulse width to a temporary
* variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the
* ECU, this value will be saved as the 'Closed' pulse width.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_CalibratePulseClosed_t;
//! Create the ECU_CalibratePulseClosed packet from parameters
void encodeECU_CalibratePulseClosedPacket(void* pkt);
//! Decode the ECU_CalibratePulseClosed packet to parameters
int decodeECU_CalibratePulseClosedPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_CalibratePulseClosed packet
#define getECU_CalibratePulseClosedPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_CalibratePulseClosed packet
#define getECU_CalibratePulseClosedMinDataLength() (1)
//! return the maximum encoded length for the ECU_CalibratePulseClosed packet
#define getECU_CalibratePulseClosedMaxDataLength() (1)
/*!
* Save the current value of the throttle output pulse width to a temporary
* variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the
* ECU, this value will be saved as the 'Open' pulse width.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_CalibratePulseOpen_t;
//! Create the ECU_CalibratePulseOpen packet from parameters
void encodeECU_CalibratePulseOpenPacket(void* pkt);
//! Decode the ECU_CalibratePulseOpen packet to parameters
int decodeECU_CalibratePulseOpenPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_CalibratePulseOpen packet
#define getECU_CalibratePulseOpenPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_CalibratePulseOpen packet
#define getECU_CalibratePulseOpenMinDataLength() (1)
//! return the maximum encoded length for the ECU_CalibratePulseOpen packet
#define getECU_CalibratePulseOpenMaxDataLength() (1)
/*!
* Configure the throttle output positions. The CALIBRATE_PULSE_CLOSED and
* CALIBRATE_PULSE_OPEN commands should have already been sent to the ECU. The
* ECU then saves the temporary values as the 'Closed' and 'Open' throttle
* output values, respectively.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_CalibratePulseWrite_t;
//! Create the ECU_CalibratePulseWrite packet from parameters
void encodeECU_CalibratePulseWritePacket(void* pkt);
//! Decode the ECU_CalibratePulseWrite packet to parameters
int decodeECU_CalibratePulseWritePacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_CalibratePulseWrite packet
#define getECU_CalibratePulseWritePacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_CalibratePulseWrite packet
#define getECU_CalibratePulseWriteMinDataLength() (1)
//! return the maximum encoded length for the ECU_CalibratePulseWrite packet
#define getECU_CalibratePulseWriteMaxDataLength() (1)
/*!
* Set one of four high-current output drivers.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint8_t driver; //!< Select driver number (1, 2, 3 or 4)
uint8_t status; //!< Set driver status (1 = ON, 0 = OFF)
}ECU_SetOutputDriver_t;
//! Create the ECU_SetOutputDriver packet from parameters
void encodeECU_SetOutputDriverPacket(void* pkt, uint8_t driver, uint8_t status);
//! Decode the ECU_SetOutputDriver packet to parameters
int decodeECU_SetOutputDriverPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* driver, uint8_t* status);
//! return the packet ID for the ECU_SetOutputDriver packet
#define getECU_SetOutputDriverPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetOutputDriver packet
#define getECU_SetOutputDriverMinDataLength() (3)
//! return the maximum encoded length for the ECU_SetOutputDriver packet
#define getECU_SetOutputDriverMaxDataLength() (3)
/*!
* Turn the throttle linearization curve either on or off.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint8_t active; //!< Curve active (1 = ON, 0 = OFF)
}ECU_SetThrottleCurveActive_t;
//! Create the ECU_SetThrottleCurveActive packet from parameters
void encodeECU_SetThrottleCurveActivePacket(void* pkt, uint8_t active);
//! Decode the ECU_SetThrottleCurveActive packet to parameters
int decodeECU_SetThrottleCurveActivePacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* active);
//! return the packet ID for the ECU_SetThrottleCurveActive packet
#define getECU_SetThrottleCurveActivePacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetThrottleCurveActive packet
#define getECU_SetThrottleCurveActiveMinDataLength() (2)
//! return the maximum encoded length for the ECU_SetThrottleCurveActive packet
#define getECU_SetThrottleCurveActiveMaxDataLength() (2)
/*!
* Set individual elements in the throttle linearization lookup table.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint8_t index; //!< Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input
float throttleOutput; //!< Percentage throttle output for this curve element
}ECU_SetThrottleCurveElement_t;
//! Create the ECU_SetThrottleCurveElement packet from parameters
void encodeECU_SetThrottleCurveElementPacket(void* pkt, uint8_t index, float throttleOutput);
//! Decode the ECU_SetThrottleCurveElement packet to parameters
int decodeECU_SetThrottleCurveElementPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* index, float* throttleOutput);
//! return the packet ID for the ECU_SetThrottleCurveElement packet
#define getECU_SetThrottleCurveElementPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetThrottleCurveElement packet
#define getECU_SetThrottleCurveElementMinDataLength() (3)
//! return the maximum encoded length for the ECU_SetThrottleCurveElement packet
#define getECU_SetThrottleCurveElementMaxDataLength() (3)
/*!
* Request the throttle curve lookup table data. If requested on CAN, the data
* will be returned on CAN. If requested on RS232, the data will be returned on
* RS232.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_RequestThrottleCurveData_t;
//! Create the ECU_RequestThrottleCurveData packet from parameters
void encodeECU_RequestThrottleCurveDataPacket(void* pkt);
//! Decode the ECU_RequestThrottleCurveData packet to parameters
int decodeECU_RequestThrottleCurveDataPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_RequestThrottleCurveData packet
#define getECU_RequestThrottleCurveDataPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_RequestThrottleCurveData packet
#define getECU_RequestThrottleCurveDataMinDataLength() (1)
//! return the maximum encoded length for the ECU_RequestThrottleCurveData packet
#define getECU_RequestThrottleCurveDataMaxDataLength() (1)
/*!
* Reset the FuelUsed value. This will set the FuelUsed data to zero.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_ResetFuelUsed_t;
//! Create the ECU_ResetFuelUsed packet from parameters
void encodeECU_ResetFuelUsedPacket(void* pkt);
//! Decode the ECU_ResetFuelUsed packet to parameters
int decodeECU_ResetFuelUsedPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_ResetFuelUsed packet
#define getECU_ResetFuelUsedPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_ResetFuelUsed packet
#define getECU_ResetFuelUsedMinDataLength() (1)
//! return the maximum encoded length for the ECU_ResetFuelUsed packet
#define getECU_ResetFuelUsedMaxDataLength() (1)
/*!
* Set the fuel used divisor
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint16_t divisor; //!< The fuel used divisor. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution).
}ECU_SetFuelUsedDivisor_t;
//! Create the ECU_SetFuelUsedDivisor packet from parameters
void encodeECU_SetFuelUsedDivisorPacket(void* pkt, uint16_t divisor);
//! Decode the ECU_SetFuelUsedDivisor packet to parameters
int decodeECU_SetFuelUsedDivisorPacket(const void* pkt, ECUSystemCommands* cmd, uint16_t* divisor);
//! return the packet ID for the ECU_SetFuelUsedDivisor packet
#define getECU_SetFuelUsedDivisorPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetFuelUsedDivisor packet
#define getECU_SetFuelUsedDivisorMinDataLength() (3)
//! return the maximum encoded length for the ECU_SetFuelUsedDivisor packet
#define getECU_SetFuelUsedDivisorMaxDataLength() (3)
/*!
* Set or clear the Fuel Used reset flag. If this flag is set, the FuelUsed
* data will reset (to zero) when the ECU is power cycled.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint8_t reset; //!< 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up
}ECU_SetFuelUsedResetFlag_t;
//! Create the ECU_SetFuelUsedResetFlag packet from parameters
void encodeECU_SetFuelUsedResetFlagPacket(void* pkt, uint8_t reset);
//! Decode the ECU_SetFuelUsedResetFlag packet to parameters
int decodeECU_SetFuelUsedResetFlagPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* reset);
//! return the packet ID for the ECU_SetFuelUsedResetFlag packet
#define getECU_SetFuelUsedResetFlagPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetFuelUsedResetFlag packet
#define getECU_SetFuelUsedResetFlagMinDataLength() (2)
//! return the maximum encoded length for the ECU_SetFuelUsedResetFlag packet
#define getECU_SetFuelUsedResetFlagMaxDataLength() (2)
/*!
* Manually set the RPM governor mode.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
ECUGovernorMode mode; //!< MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command
}ECU_SetGovernorMode_t;
//! Create the ECU_SetGovernorMode packet from parameters
void encodeECU_SetGovernorModePacket(void* pkt, ECUGovernorMode mode);
//! Decode the ECU_SetGovernorMode packet to parameters
int decodeECU_SetGovernorModePacket(const void* pkt, ECUSystemCommands* cmd, ECUGovernorMode* mode);
//! return the packet ID for the ECU_SetGovernorMode packet
#define getECU_SetGovernorModePacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetGovernorMode packet
#define getECU_SetGovernorModeMinDataLength() (2)
//! return the maximum encoded length for the ECU_SetGovernorMode packet
#define getECU_SetGovernorModeMaxDataLength() (2)
/*!
* Set the serial mode used for Autronic relay. When Autronic relay is enabled
* the external serial port of the ECU is reconfigured to connect to ECUCal,
* relaying bytes to the internal autronic processor; while still allowing the
* auxiliary processor to see telemetry from Autronic. This is fundamentally
* different from using the switch to calibration mode, which bypasses the
* auxiliary processor altogether, cutting it off from autronic telemetry.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
ECUAutronicRelayState mode; //!< The serial relay mode to command
}ECU_SetSerialMode_t;
//! Create the ECU_SetSerialMode packet from parameters
void encodeECU_SetSerialModePacket(void* pkt, ECUAutronicRelayState mode);
//! Decode the ECU_SetSerialMode packet to parameters
int decodeECU_SetSerialModePacket(const void* pkt, ECUSystemCommands* cmd, ECUAutronicRelayState* mode);
//! return the packet ID for the ECU_SetSerialMode packet
#define getECU_SetSerialModePacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetSerialMode packet
#define getECU_SetSerialModeMinDataLength() (2)
//! return the maximum encoded length for the ECU_SetSerialMode packet
#define getECU_SetSerialModeMaxDataLength() (2)
/*!
* Set a custom address value for the ECU.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint16_t address; //!< ECU address in the range {1, 65534}
}ECU_SetECUAddress_t;
//! Create the ECU_SetECUAddress packet from parameters
void encodeECU_SetECUAddressPacket(void* pkt, uint16_t address);
//! Decode the ECU_SetECUAddress packet to parameters
int decodeECU_SetECUAddressPacket(const void* pkt, ECUSystemCommands* cmd, uint16_t* address);
//! return the packet ID for the ECU_SetECUAddress packet
#define getECU_SetECUAddressPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetECUAddress packet
#define getECU_SetECUAddressMinDataLength() (3)
//! return the maximum encoded length for the ECU_SetECUAddress packet
#define getECU_SetECUAddressMaxDataLength() (3)
/*!
* Save a single byte of USER_DATA in EEPROM.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint8_t index; //!< USER_DATA address (0 to 7)
uint8_t userdata; //!< USER_DATA variable
}ECU_SetUserData_t;
//! Create the ECU_SetUserData packet from parameters
void encodeECU_SetUserDataPacket(void* pkt, uint8_t index, uint8_t userdata);
//! Decode the ECU_SetUserData packet to parameters
int decodeECU_SetUserDataPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* index, uint8_t* userdata);
//! return the packet ID for the ECU_SetUserData packet
#define getECU_SetUserDataPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_SetUserData packet
#define getECU_SetUserDataMinDataLength() (3)
//! return the maximum encoded length for the ECU_SetUserData packet
#define getECU_SetUserDataMaxDataLength() (3)
/*!
* Reset the engine runtime.
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
uint32_t time; //!< The new value of the engine time counter in seconds
}ECU_ResetEngineTime_t;
//! Create the ECU_ResetEngineTime packet from parameters
void encodeECU_ResetEngineTimePacket(void* pkt, uint32_t time);
//! Decode the ECU_ResetEngineTime packet to parameters
int decodeECU_ResetEngineTimePacket(const void* pkt, ECUSystemCommands* cmd, uint32_t* time);
//! return the packet ID for the ECU_ResetEngineTime packet
#define getECU_ResetEngineTimePacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_ResetEngineTime packet
#define getECU_ResetEngineTimeMinDataLength() (1)
//! return the maximum encoded length for the ECU_ResetEngineTime packet
#define getECU_ResetEngineTimeMaxDataLength() (4)
/*!
* Reset the ECU
*/
typedef struct
{
ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant.
}ECU_ResetECU_t;
//! Create the ECU_ResetECU packet from parameters
void encodeECU_ResetECUPacket(void* pkt);
//! Decode the ECU_ResetECU packet to parameters
int decodeECU_ResetECUPacket(const void* pkt, ECUSystemCommands* cmd);
//! return the packet ID for the ECU_ResetECU packet
#define getECU_ResetECUPacketID() (PKT_ECU_SYS_CMD)
//! return the minimum encoded length for the ECU_ResetECU packet
#define getECU_ResetECUMinDataLength() (4)
//! return the maximum encoded length for the ECU_ResetECU packet
#define getECU_ResetECUMaxDataLength() (4)
#ifdef __cplusplus
}
#endif
#endif // _ECUPACKETS_H