mirror of https://github.com/ArduPilot/ardupilot
4024 lines
152 KiB
C
4024 lines
152 KiB
C
|
// ECUPackets.c was generated by ProtoGen version 3.2.a
|
||
|
|
||
|
/*
|
||
|
* Copyright Currawong Engineering Pty Ltd
|
||
|
* www.currawongeng.com
|
||
|
* all rights reserved
|
||
|
*/
|
||
|
|
||
|
|
||
|
#include "ECUPackets.h"
|
||
|
#include "fielddecode.h"
|
||
|
#include "fieldencode.h"
|
||
|
#include "scaleddecode.h"
|
||
|
#include "scaledencode.h"
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ThrottleCommand packet
|
||
|
*
|
||
|
* The throttle command packet sets the throttle position setpoint. The ECU
|
||
|
* will adjust the throttle position based on this command.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param throttleCommand is Commanded throttle position in percent
|
||
|
*/
|
||
|
void encodeECU_ThrottleCommandPacket(void* _pg_pkt, float throttleCommand)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Commanded throttle position in percent
|
||
|
// Range of throttleCommand is 0.0f to 100.0f.
|
||
|
float32ScaledTo2UnsignedBeBytes(throttleCommand, _pg_data, &_pg_byteindex, 0.0f, 655.35f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCommandPacketID());
|
||
|
|
||
|
}// encodeECU_ThrottleCommandPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ThrottleCommand packet
|
||
|
*
|
||
|
* The throttle command packet sets the throttle position setpoint. The ECU
|
||
|
* will adjust the throttle position based on this command.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param throttleCommand receives Commanded throttle position in percent
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ThrottleCommandPacket(const void* _pg_pkt, float* throttleCommand)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ThrottleCommandPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ThrottleCommandMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Commanded throttle position in percent
|
||
|
// Range of throttleCommand is 0.0f to 100.0f.
|
||
|
(*throttleCommand) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/655.35f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ThrottleCommandPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_RPMCommand packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_RPMCommandPacketStructure(void* _pg_pkt, const ECU_RPMCommand_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
|
||
|
// RPM command in units of 50 RPM
|
||
|
// Range of rpmCmdHigh is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->rpmCmdHigh, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Low part of RPM command from 0 to 49
|
||
|
// Range of rpmCmdLow is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->rpmCmdLow, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Reconstruct the RPM command
|
||
|
_pg_data[0] = (uint8_t)((_pg_user->rpmCmd)/50); _pg_data[1] = (uint8_t)((_pg_user->rpmCmd) - _pg_data[0]*50);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_RPMCommandPacketID());
|
||
|
|
||
|
}// encodeECU_RPMCommandPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_RPMCommand packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_RPMCommandPacketStructure(const void* _pg_pkt, ECU_RPMCommand_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_RPMCommandPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_RPMCommandMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// RPM command in units of 50 RPM
|
||
|
// Range of rpmCmdHigh is 0 to 255.
|
||
|
_pg_user->rpmCmdHigh = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Low part of RPM command from 0 to 49
|
||
|
// Range of rpmCmdLow is 0 to 255.
|
||
|
_pg_user->rpmCmdLow = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Reconstruct the RPM command
|
||
|
_pg_user->rpmCmd = (uint16_t)(_pg_user->rpmCmdHigh*50 + _pg_user->rpmCmdLow);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_RPMCommandPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Encode a ECU_ecuStatusBits_t into a byte array
|
||
|
*
|
||
|
|
||
|
* \param _pg_data points to the byte array to add encoded data to
|
||
|
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes.
|
||
|
* \param _pg_user is the data to encode in the byte array
|
||
|
*/
|
||
|
void encodeECU_ecuStatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ecuStatusBits_t* _pg_user)
|
||
|
{
|
||
|
int _pg_byteindex = *_pg_bytecount;
|
||
|
|
||
|
// 1 if driver 8 is on
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->driverPin8 == true) ? 1 : 0) << 7;
|
||
|
|
||
|
// 1 if driver 7 is on
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->driverPin7 == true) ? 1 : 0) << 6;
|
||
|
|
||
|
// 1 if driver 2 is on
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->driverPin2 == true) ? 1 : 0) << 5;
|
||
|
|
||
|
// 1 if driver 1 is on
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->driverPin1 == true) ? 1 : 0) << 4;
|
||
|
|
||
|
// 1 if the throttle curve is on.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->throttleCurveOn == true) ? 1 : 0) << 3;
|
||
|
|
||
|
// 1 if autronic, else auxiliary.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->rs232mode == true) ? 1 : 0) << 2;
|
||
|
|
||
|
// 1 if any errors are set - refer to [error packet](#PKT_ECU_ERROR_MSG)
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->errorIndicator == true) ? 1 : 0) << 1;
|
||
|
|
||
|
// Global enable based on physical input
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->enabled == true) ? 1 : 0);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
*_pg_bytecount = _pg_byteindex;
|
||
|
|
||
|
}// encodeECU_ecuStatusBits_t
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode a ECU_ecuStatusBits_t from a byte array
|
||
|
*
|
||
|
|
||
|
* \param _pg_data points to the byte array to decoded data from
|
||
|
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
|
||
|
* \param _pg_user is the data to decode from the byte array
|
||
|
* \return 1 if the data are decoded, else 0.
|
||
|
*/
|
||
|
int decodeECU_ecuStatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ecuStatusBits_t* _pg_user)
|
||
|
{
|
||
|
int _pg_byteindex = *_pg_bytecount;
|
||
|
|
||
|
// 1 if driver 8 is on
|
||
|
_pg_user->driverPin8 = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
|
||
|
|
||
|
// 1 if driver 7 is on
|
||
|
_pg_user->driverPin7 = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
|
||
|
|
||
|
// 1 if driver 2 is on
|
||
|
_pg_user->driverPin2 = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
|
||
|
|
||
|
// 1 if driver 1 is on
|
||
|
_pg_user->driverPin1 = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
|
||
|
|
||
|
// 1 if the throttle curve is on.
|
||
|
_pg_user->throttleCurveOn = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
|
||
|
|
||
|
// 1 if autronic, else auxiliary.
|
||
|
_pg_user->rs232mode = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
|
||
|
|
||
|
// 1 if any errors are set - refer to [error packet](#PKT_ECU_ERROR_MSG)
|
||
|
_pg_user->errorIndicator = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
|
||
|
|
||
|
// Global enable based on physical input
|
||
|
_pg_user->enabled = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
*_pg_bytecount = _pg_byteindex;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ecuStatusBits_t
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TelemetryFast packet
|
||
|
*
|
||
|
* 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)
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_TelemetryFastPacketStructure(void* _pg_pkt, const ECU_TelemetryFast_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Throttle signal (0 to 100%)
|
||
|
// Range of throttle is 0.0f to 100.0f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->throttle, _pg_data, &_pg_byteindex, 0.0f, 2.55f);
|
||
|
|
||
|
// Engine speed in revolutions per minute
|
||
|
// Range of rpm is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->rpm, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fuel used in grams
|
||
|
// Range of fuelUsed is 0 to 4294967295.
|
||
|
uint32ToBeBytes(_pg_user->fuelUsed, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
encodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, &_pg_user->ecuStatusBits);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetryFastPacketID());
|
||
|
|
||
|
}// encodeECU_TelemetryFastPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TelemetryFast packet
|
||
|
*
|
||
|
* 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)
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TelemetryFastPacketStructure(const void* _pg_pkt, ECU_TelemetryFast_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TelemetryFastPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_TelemetryFastMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Throttle signal (0 to 100%)
|
||
|
// Range of throttle is 0.0f to 100.0f.
|
||
|
_pg_user->throttle = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.55f);
|
||
|
|
||
|
// Engine speed in revolutions per minute
|
||
|
// Range of rpm is 0 to 65535.
|
||
|
_pg_user->rpm = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fuel used in grams
|
||
|
// Range of fuelUsed is 0 to 4294967295.
|
||
|
_pg_user->fuelUsed = uint32FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
if(decodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, &_pg_user->ecuStatusBits) == 0)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TelemetryFastPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TelemetryFast packet
|
||
|
*
|
||
|
* 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)
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param throttle is Throttle signal (0 to 100%)
|
||
|
* \param rpm is Engine speed in revolutions per minute
|
||
|
* \param fuelUsed is Fuel used in grams
|
||
|
* \param ecuStatusBits is
|
||
|
*/
|
||
|
void encodeECU_TelemetryFastPacket(void* _pg_pkt, float throttle, uint16_t rpm, uint32_t fuelUsed, const ECU_ecuStatusBits_t* ecuStatusBits)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Throttle signal (0 to 100%)
|
||
|
// Range of throttle is 0.0f to 100.0f.
|
||
|
float32ScaledTo1UnsignedBytes(throttle, _pg_data, &_pg_byteindex, 0.0f, 2.55f);
|
||
|
|
||
|
// Engine speed in revolutions per minute
|
||
|
// Range of rpm is 0 to 65535.
|
||
|
uint16ToBeBytes(rpm, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fuel used in grams
|
||
|
// Range of fuelUsed is 0 to 4294967295.
|
||
|
uint32ToBeBytes(fuelUsed, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
encodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, ecuStatusBits);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetryFastPacketID());
|
||
|
|
||
|
}// encodeECU_TelemetryFastPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TelemetryFast packet
|
||
|
*
|
||
|
* 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)
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param throttle receives Throttle signal (0 to 100%)
|
||
|
* \param rpm receives Engine speed in revolutions per minute
|
||
|
* \param fuelUsed receives Fuel used in grams
|
||
|
* \param ecuStatusBits receives
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TelemetryFastPacket(const void* _pg_pkt, float* throttle, uint16_t* rpm, uint32_t* fuelUsed, ECU_ecuStatusBits_t* ecuStatusBits)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TelemetryFastPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_TelemetryFastMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Throttle signal (0 to 100%)
|
||
|
// Range of throttle is 0.0f to 100.0f.
|
||
|
(*throttle) = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.55f);
|
||
|
|
||
|
// Engine speed in revolutions per minute
|
||
|
// Range of rpm is 0 to 65535.
|
||
|
(*rpm) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fuel used in grams
|
||
|
// Range of fuelUsed is 0 to 4294967295.
|
||
|
(*fuelUsed) = uint32FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
if(decodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, ecuStatusBits) == 0)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TelemetryFastPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TelemetrySlow0 packet
|
||
|
*
|
||
|
* 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).
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_TelemetrySlow0PacketStructure(void* _pg_pkt, const ECU_TelemetrySlow0_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned int _pg_tempbitfield = 0;
|
||
|
|
||
|
|
||
|
|
||
|
// RPM command in units of 50 RPM
|
||
|
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Source of the throttle information
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->throttleSrc << 4;
|
||
|
|
||
|
// Throttle pulse width in microseconds
|
||
|
// Range of throttlePulse is 0 to 4095.
|
||
|
_pg_tempbitfield = (unsigned int)limitMax(_pg_user->throttlePulse, 4095);
|
||
|
_pg_data[_pg_byteindex + 1] = (uint8_t)_pg_tempbitfield;
|
||
|
|
||
|
_pg_tempbitfield >>= 8;
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)_pg_tempbitfield;
|
||
|
_pg_byteindex += 2; // close bit field
|
||
|
|
||
|
|
||
|
// Cylinder head temperature in Celsius
|
||
|
// Range of cht is -10.0f to 245.0f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->cht, _pg_data, &_pg_byteindex, -10.0f, 1.0f);
|
||
|
|
||
|
// Low part of RPM command from 0 to 49
|
||
|
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Barometric pressure in kilo-Pascals
|
||
|
// Range of baro is 0.0f to 131.07f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->baro, _pg_data, &_pg_byteindex, 0.0f, 500.0f);
|
||
|
|
||
|
// Percentage ratio of manifold pressure to barometric pressure
|
||
|
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Reconstruct the RPM command
|
||
|
_pg_data[0] = (uint8_t)(_pg_user->rpmCmd/50); _pg_data[4] = (uint8_t)(_pg_user->rpmCmd - _pg_data[0]*50);
|
||
|
|
||
|
// Reconstruct the manifold pressure
|
||
|
_pg_data[7] = (uint8_t)(0.5f + 100.0f*_pg_user->map/_pg_user->baro);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySlow0PacketID());
|
||
|
|
||
|
}// encodeECU_TelemetrySlow0PacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TelemetrySlow0 packet
|
||
|
*
|
||
|
* 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).
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TelemetrySlow0PacketStructure(const void* _pg_pkt, ECU_TelemetrySlow0_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
unsigned int _pg_tempbitfield = 0;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TelemetrySlow0PacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_TelemetrySlow0MinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// RPM command in units of 50 RPM
|
||
|
_pg_byteindex += 1;
|
||
|
|
||
|
// Source of the throttle information
|
||
|
_pg_user->throttleSrc = (ECUThrottleSource)(_pg_data[_pg_byteindex] >> 4);
|
||
|
|
||
|
// Throttle pulse width in microseconds
|
||
|
// Range of throttlePulse is 0 to 4095.
|
||
|
_pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xF);
|
||
|
|
||
|
_pg_tempbitfield <<= 8;
|
||
|
_pg_tempbitfield |= _pg_data[_pg_byteindex + 1];
|
||
|
|
||
|
_pg_user->throttlePulse = _pg_tempbitfield;
|
||
|
_pg_byteindex += 2; // close bit field
|
||
|
|
||
|
// Cylinder head temperature in Celsius
|
||
|
// Range of cht is -10.0f to 245.0f.
|
||
|
_pg_user->cht = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, -10.0f, 1.0f/1.0f);
|
||
|
|
||
|
// Low part of RPM command from 0 to 49
|
||
|
_pg_byteindex += 1;
|
||
|
|
||
|
// Barometric pressure in kilo-Pascals
|
||
|
// Range of baro is 0.0f to 131.07f.
|
||
|
_pg_user->baro = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/500.0f);
|
||
|
|
||
|
// Percentage ratio of manifold pressure to barometric pressure
|
||
|
_pg_byteindex += 1;
|
||
|
|
||
|
// Reconstruct the RPM command
|
||
|
_pg_user->rpmCmd = (uint16_t)(_pg_data[0]*50 + _pg_data[4]);
|
||
|
|
||
|
// Reconstruct the manifold pressure
|
||
|
_pg_user->map = _pg_data[7]*0.01f*_pg_user->baro;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TelemetrySlow0PacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TelemetrySlow1 packet
|
||
|
*
|
||
|
* The second of three slow telemetry packets
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_TelemetrySlow1PacketStructure(void* _pg_pkt, const ECU_TelemetrySlow1_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Inlet air temperature in Celsius
|
||
|
// Range of mat is -127.0f to 127.0f.
|
||
|
float32ScaledTo1SignedBytes(_pg_user->mat, _pg_data, &_pg_byteindex, 1.0f);
|
||
|
|
||
|
// Fuel pressure in kilo-Pascals
|
||
|
// Range of fuelPressure is 0.0f to 1310.7f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->fuelPressure, _pg_data, &_pg_byteindex, 0.0f, 50.0f);
|
||
|
|
||
|
// Engine run time in seconds.
|
||
|
// Range of hobbs is 0 to 16777215.
|
||
|
uint24ToBeBytes((uint32_t)(limitMax(_pg_user->hobbs, 16777215)), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Input voltage in Volts
|
||
|
// Range of voltage is 0.0f to 25.5f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->voltage, _pg_data, &_pg_byteindex, 0.0f, 10.0f);
|
||
|
|
||
|
_pg_data[_pg_byteindex] = 0;
|
||
|
|
||
|
// Operational mode of the governor
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->governorMode;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySlow1PacketID());
|
||
|
|
||
|
}// encodeECU_TelemetrySlow1PacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TelemetrySlow1 packet
|
||
|
*
|
||
|
* The second of three slow telemetry packets
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TelemetrySlow1PacketStructure(const void* _pg_pkt, ECU_TelemetrySlow1_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TelemetrySlow1PacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_TelemetrySlow1MinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Inlet air temperature in Celsius
|
||
|
// Range of mat is -127.0f to 127.0f.
|
||
|
_pg_user->mat = float32ScaledFrom1SignedBytes(_pg_data, &_pg_byteindex, 1.0f/1.0f);
|
||
|
|
||
|
// Fuel pressure in kilo-Pascals
|
||
|
// Range of fuelPressure is 0.0f to 1310.7f.
|
||
|
_pg_user->fuelPressure = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/50.0f);
|
||
|
|
||
|
// Engine run time in seconds.
|
||
|
// Range of hobbs is 0 to 16777215.
|
||
|
_pg_user->hobbs = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Input voltage in Volts
|
||
|
// Range of voltage is 0.0f to 25.5f.
|
||
|
_pg_user->voltage = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10.0f);
|
||
|
|
||
|
// Operational mode of the governor
|
||
|
_pg_user->governorMode = (ECUGovernorMode)((_pg_data[_pg_byteindex]) & 0x7);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TelemetrySlow1PacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TelemetrySlow2 packet
|
||
|
*
|
||
|
* The third of three slow telemetry packets
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_TelemetrySlow2PacketStructure(void* _pg_pkt, const ECU_TelemetrySlow2_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// CPU load in percent
|
||
|
// Range of cpuLoad is 0.0f to 255.0f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->cpuLoad, _pg_data, &_pg_byteindex, 0.0f, 1.0f);
|
||
|
|
||
|
// Charge temperature in Celsius
|
||
|
// Range of chargeTemp is -128.0f to 254.5f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->chargeTemp, _pg_data, &_pg_byteindex, -128.0f, 0.666666667f);
|
||
|
|
||
|
// Injector duty cycle in percent
|
||
|
// Range of injectorDuty is 0.0f to 6553.5f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->injectorDuty, _pg_data, &_pg_byteindex, 0.0f, 10.0f);
|
||
|
|
||
|
// First ignition advance angle in degrees
|
||
|
// Range of ignAngle1 is 0.0f to 127.5f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->ignAngle1, _pg_data, &_pg_byteindex, 0.0f, 2.0f);
|
||
|
|
||
|
// Second ignition advance angle in degrees
|
||
|
// Range of ignAngle2 is 0.0f to 127.5f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->ignAngle2, _pg_data, &_pg_byteindex, 0.0f, 2.0f);
|
||
|
|
||
|
// Fuel flow rate in grams per minute
|
||
|
// Range of flowRate is 0.0f to 1092.25f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->flowRate, _pg_data, &_pg_byteindex, 0.0f, 60.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySlow2PacketID());
|
||
|
|
||
|
}// encodeECU_TelemetrySlow2PacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TelemetrySlow2 packet
|
||
|
*
|
||
|
* The third of three slow telemetry packets
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TelemetrySlow2PacketStructure(const void* _pg_pkt, ECU_TelemetrySlow2_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TelemetrySlow2PacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_TelemetrySlow2MinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// CPU load in percent
|
||
|
// Range of cpuLoad is 0.0f to 255.0f.
|
||
|
_pg_user->cpuLoad = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1.0f);
|
||
|
|
||
|
// Charge temperature in Celsius
|
||
|
// Range of chargeTemp is -128.0f to 254.5f.
|
||
|
_pg_user->chargeTemp = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, -128.0f, 1.0f/0.666666667f);
|
||
|
|
||
|
// Injector duty cycle in percent
|
||
|
// Range of injectorDuty is 0.0f to 6553.5f.
|
||
|
_pg_user->injectorDuty = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10.0f);
|
||
|
|
||
|
// First ignition advance angle in degrees
|
||
|
// Range of ignAngle1 is 0.0f to 127.5f.
|
||
|
_pg_user->ignAngle1 = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f);
|
||
|
|
||
|
// Second ignition advance angle in degrees
|
||
|
// Range of ignAngle2 is 0.0f to 127.5f.
|
||
|
_pg_user->ignAngle2 = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f);
|
||
|
|
||
|
// Fuel flow rate in grams per minute
|
||
|
// Range of flowRate is 0.0f to 1092.25f.
|
||
|
_pg_user->flowRate = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/60.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TelemetrySlow2PacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_HardwareConfig packet
|
||
|
*
|
||
|
* The hardware config packet contains the ECU serial number and various ECU
|
||
|
* configuration data. Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_HardwareConfigPacketStructure(void* _pg_pkt, const ECU_HardwareConfig_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// ECU serial number
|
||
|
// Range of serialNumber is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->serialNumber, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// 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)
|
||
|
// Range of fuelDivisor is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->fuelDivisor, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
_pg_data[_pg_byteindex] = 0;
|
||
|
|
||
|
// Autronic relay state. This is a volatile status which will reset to AUT_RELAY_OFF on ECU power cycle.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->relayState << 1;
|
||
|
|
||
|
// Set if the fuel used value is reset each on each ECU power cycle
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->resetFuelUsedOnStart == true) ? 1 : 0);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_HardwareConfigPacketID());
|
||
|
|
||
|
}// encodeECU_HardwareConfigPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_HardwareConfig packet
|
||
|
*
|
||
|
* The hardware config packet contains the ECU serial number and various ECU
|
||
|
* configuration data. Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_HardwareConfigPacketStructure(const void* _pg_pkt, ECU_HardwareConfig_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_HardwareConfigPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_HardwareConfigMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// ECU serial number
|
||
|
// Range of serialNumber is 0 to 65535.
|
||
|
_pg_user->serialNumber = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// 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)
|
||
|
// Range of fuelDivisor is 0 to 65535.
|
||
|
_pg_user->fuelDivisor = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Autronic relay state. This is a volatile status which will reset to AUT_RELAY_OFF on ECU power cycle.
|
||
|
_pg_user->relayState = (ECUAutronicRelayState)((_pg_data[_pg_byteindex] >> 1) & 0x3);
|
||
|
|
||
|
// Set if the fuel used value is reset each on each ECU power cycle
|
||
|
_pg_user->resetFuelUsedOnStart = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_HardwareConfigPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_Version packet
|
||
|
*
|
||
|
* The software version packet contains the auxiliary processor firmware
|
||
|
* version information. Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_VersionPacketStructure(void* _pg_pkt, const ECU_Version_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// 1 = Release version, 0 = Testing version
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->release == true) ? 1 : 0) << 7;
|
||
|
|
||
|
// Reserved for future use
|
||
|
|
||
|
// Major version number
|
||
|
// Range of versionMajor is 0 to 63.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->versionMajor;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
|
||
|
// Minor version number
|
||
|
// Range of versionMinor is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->versionMinor, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Revision number
|
||
|
// Range of versionRev is 0 to 15.
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)limitMax(_pg_user->versionRev, 15) << 4;
|
||
|
|
||
|
// The release month from 1 (January) to 12 (December)
|
||
|
// Range of month is 0 to 15.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->month, 15);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
|
||
|
// The release day of month from 1 to 31
|
||
|
// Range of day is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->day, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The release year
|
||
|
// Range of year is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->year, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Firmware checksum
|
||
|
// Range of checksum is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->checksum, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_VersionPacketID());
|
||
|
|
||
|
}// encodeECU_VersionPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_Version packet
|
||
|
*
|
||
|
* The software version packet contains the auxiliary processor firmware
|
||
|
* version information. Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_VersionPacketStructure(const void* _pg_pkt, ECU_Version_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_VersionPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_VersionMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// 1 = Release version, 0 = Testing version
|
||
|
_pg_user->release = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
|
||
|
|
||
|
// Reserved for future use
|
||
|
|
||
|
// Major version number
|
||
|
// Range of versionMajor is 0 to 63.
|
||
|
_pg_user->versionMajor = ((_pg_data[_pg_byteindex]) & 0x3F);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// Minor version number
|
||
|
// Range of versionMinor is 0 to 255.
|
||
|
_pg_user->versionMinor = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Revision number
|
||
|
// Range of versionRev is 0 to 15.
|
||
|
_pg_user->versionRev = (_pg_data[_pg_byteindex] >> 4);
|
||
|
|
||
|
// The release month from 1 (January) to 12 (December)
|
||
|
// Range of month is 0 to 15.
|
||
|
_pg_user->month = ((_pg_data[_pg_byteindex]) & 0xF);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// The release day of month from 1 to 31
|
||
|
// Range of day is 0 to 255.
|
||
|
_pg_user->day = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The release year
|
||
|
// Range of year is 0 to 65535.
|
||
|
_pg_user->year = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Firmware checksum
|
||
|
// Range of checksum is 0 to 65535.
|
||
|
_pg_user->checksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_VersionPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_Errors packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_ErrorsPacketStructure(void* _pg_pkt, const ECU_Errors_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Error bits for the Autronic processor
|
||
|
encodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronicErrors);
|
||
|
|
||
|
// Error bits for the auxiliary processor
|
||
|
encodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliaryErrors);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ErrorsPacketID());
|
||
|
|
||
|
}// encodeECU_ErrorsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_Errors packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ErrorsPacketStructure(const void* _pg_pkt, ECU_Errors_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ErrorsPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_ErrorsMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Error bits for the Autronic processor
|
||
|
if(decodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronicErrors) == 0)
|
||
|
return 0;
|
||
|
|
||
|
// Error bits for the auxiliary processor
|
||
|
if(decodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliaryErrors) == 0)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ErrorsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_PowerCycles packet
|
||
|
*
|
||
|
* The power cycles packet contains information on the reset condition of the
|
||
|
* ECU. Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_PowerCyclesPacketStructure(void* _pg_pkt, const ECU_PowerCycles_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Number of power cycles
|
||
|
// Range of powerCycles is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Range of reserved is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->reserved, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Auxiliary processor reset code
|
||
|
// Range of resetCode is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->resetCode, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Milliseconds since system reset
|
||
|
// Range of systemTime is 0 to 4294967295.
|
||
|
uint32ToBeBytes(_pg_user->systemTime, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PowerCyclesPacketID());
|
||
|
|
||
|
}// encodeECU_PowerCyclesPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_PowerCycles packet
|
||
|
*
|
||
|
* The power cycles packet contains information on the reset condition of the
|
||
|
* ECU. Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_PowerCyclesPacketStructure(const void* _pg_pkt, ECU_PowerCycles_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_PowerCyclesPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_PowerCyclesMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Number of power cycles
|
||
|
// Range of powerCycles is 0 to 65535.
|
||
|
_pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Range of reserved is 0 to 255.
|
||
|
_pg_user->reserved = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Auxiliary processor reset code
|
||
|
// Range of resetCode is 0 to 255.
|
||
|
_pg_user->resetCode = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Milliseconds since system reset
|
||
|
// Range of systemTime is 0 to 4294967295.
|
||
|
_pg_user->systemTime = uint32FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_PowerCyclesPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_PumpDebug packet
|
||
|
*
|
||
|
* The fuel pump debug packet contains information on the pump control system.
|
||
|
* Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_PumpDebugPacketStructure(void* _pg_pkt, const ECU_PumpDebug_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Proportional term of the pump feedback control in percent
|
||
|
// Range of pTerm is -3276.7f to 3276.7f.
|
||
|
float32ScaledTo2SignedBeBytes(_pg_user->pTerm, _pg_data, &_pg_byteindex, 10.0f);
|
||
|
|
||
|
// Integral term of the pump feedback control in percent
|
||
|
// Range of iTerm is -3276.7f to 3276.7f.
|
||
|
float32ScaledTo2SignedBeBytes(_pg_user->iTerm, _pg_data, &_pg_byteindex, 10.0f);
|
||
|
|
||
|
// Pump duty cycle in percent
|
||
|
// Range of dutyCycle is 0.0f to 6553.5f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->dutyCycle, _pg_data, &_pg_byteindex, 0.0f, 10.0f);
|
||
|
|
||
|
// Fuel pressure in kilo-Pascals
|
||
|
// Range of fuelPressure is 0.0f to 1310.7f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->fuelPressure, _pg_data, &_pg_byteindex, 0.0f, 50.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PumpDebugPacketID());
|
||
|
|
||
|
}// encodeECU_PumpDebugPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_PumpDebug packet
|
||
|
*
|
||
|
* The fuel pump debug packet contains information on the pump control system.
|
||
|
* Send a zero length packet to request this data.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_PumpDebugPacketStructure(const void* _pg_pkt, ECU_PumpDebug_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_PumpDebugPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_PumpDebugMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Proportional term of the pump feedback control in percent
|
||
|
// Range of pTerm is -3276.7f to 3276.7f.
|
||
|
_pg_user->pTerm = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f);
|
||
|
|
||
|
// Integral term of the pump feedback control in percent
|
||
|
// Range of iTerm is -3276.7f to 3276.7f.
|
||
|
_pg_user->iTerm = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f);
|
||
|
|
||
|
// Pump duty cycle in percent
|
||
|
// Range of dutyCycle is 0.0f to 6553.5f.
|
||
|
_pg_user->dutyCycle = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10.0f);
|
||
|
|
||
|
// Fuel pressure in kilo-Pascals
|
||
|
// Range of fuelPressure is 0.0f to 1310.7f.
|
||
|
_pg_user->fuelPressure = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/50.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_PumpDebugPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TotalEngineTime packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param hobbs is Total engine run time in seconds
|
||
|
*/
|
||
|
void encodeECU_TotalEngineTimePacket(void* _pg_pkt, uint32_t hobbs)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Total engine run time in seconds
|
||
|
// Range of hobbs is 0 to 16777215.
|
||
|
uint24ToBeBytes((uint32_t)(limitMax(hobbs, 16777215)), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TotalEngineTimePacketID());
|
||
|
|
||
|
}// encodeECU_TotalEngineTimePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TotalEngineTime packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param hobbs receives Total engine run time in seconds
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TotalEngineTimePacket(const void* _pg_pkt, uint32_t* hobbs)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TotalEngineTimePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_TotalEngineTimeMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Total engine run time in seconds
|
||
|
// Range of hobbs is 0 to 16777215.
|
||
|
(*hobbs) = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TotalEngineTimePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_eepromSettings packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_eepromSettingsPacketStructure(void* _pg_pkt, const ECU_eepromSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Version of the EEPROM data
|
||
|
// Range of eepromVersion is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->eepromVersion, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Number of bytes of the EEPROM data
|
||
|
// Range of eepromSize is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->eepromSize, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fletcher's checksum of the EEPROM data
|
||
|
// Range of eepromChecksum is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->eepromChecksum, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// ECU compilation options
|
||
|
encodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, &_pg_user->compileOptions);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_eepromSettingsPacketID());
|
||
|
|
||
|
}// encodeECU_eepromSettingsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_eepromSettings packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_eepromSettingsPacketStructure(const void* _pg_pkt, ECU_eepromSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_eepromSettingsPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_eepromSettingsMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Version of the EEPROM data
|
||
|
// Range of eepromVersion is 0 to 255.
|
||
|
_pg_user->eepromVersion = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Number of bytes of the EEPROM data
|
||
|
// Range of eepromSize is 0 to 65535.
|
||
|
_pg_user->eepromSize = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fletcher's checksum of the EEPROM data
|
||
|
// Range of eepromChecksum is 0 to 65535.
|
||
|
_pg_user->eepromChecksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// ECU compilation options
|
||
|
if(decodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, &_pg_user->compileOptions) == 0)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_eepromSettingsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_eepromSettings packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param eepromVersion is Version of the EEPROM data
|
||
|
* \param eepromSize is Number of bytes of the EEPROM data
|
||
|
* \param eepromChecksum is Fletcher's checksum of the EEPROM data
|
||
|
* \param compileOptions is ECU compilation options
|
||
|
*/
|
||
|
void encodeECU_eepromSettingsPacket(void* _pg_pkt, uint8_t eepromVersion, uint16_t eepromSize, uint16_t eepromChecksum, const ECU_CompileOptions_t* compileOptions)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Version of the EEPROM data
|
||
|
// Range of eepromVersion is 0 to 255.
|
||
|
uint8ToBytes(eepromVersion, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Number of bytes of the EEPROM data
|
||
|
// Range of eepromSize is 0 to 65535.
|
||
|
uint16ToBeBytes(eepromSize, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fletcher's checksum of the EEPROM data
|
||
|
// Range of eepromChecksum is 0 to 65535.
|
||
|
uint16ToBeBytes(eepromChecksum, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// ECU compilation options
|
||
|
encodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, compileOptions);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_eepromSettingsPacketID());
|
||
|
|
||
|
}// encodeECU_eepromSettingsPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_eepromSettings packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param eepromVersion receives Version of the EEPROM data
|
||
|
* \param eepromSize receives Number of bytes of the EEPROM data
|
||
|
* \param eepromChecksum receives Fletcher's checksum of the EEPROM data
|
||
|
* \param compileOptions receives ECU compilation options
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_eepromSettingsPacket(const void* _pg_pkt, uint8_t* eepromVersion, uint16_t* eepromSize, uint16_t* eepromChecksum, ECU_CompileOptions_t* compileOptions)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_eepromSettingsPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_eepromSettingsMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Version of the EEPROM data
|
||
|
// Range of eepromVersion is 0 to 255.
|
||
|
(*eepromVersion) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Number of bytes of the EEPROM data
|
||
|
// Range of eepromSize is 0 to 65535.
|
||
|
(*eepromSize) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Fletcher's checksum of the EEPROM data
|
||
|
// Range of eepromChecksum is 0 to 65535.
|
||
|
(*eepromChecksum) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// ECU compilation options
|
||
|
if(decodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, compileOptions) == 0)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_eepromSettingsPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CHTLoopSettings packet
|
||
|
*
|
||
|
* Control loop settings for the CHT control loop
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_CHTLoopSettingsPacketStructure(void* _pg_pkt, const ECU_CHTLoopSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
_pg_data[_pg_byteindex] = 0;
|
||
|
|
||
|
// Filter value for derivative term
|
||
|
// Range of dTermFilter is 0 to 31.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->dTermFilter, 31) << 1;
|
||
|
|
||
|
// CHT control loop enabled
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->enabled == true) ? 1 : 0);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
|
||
|
// Target CHT temperature
|
||
|
// Range of targetTemp is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->targetTemp, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Proportaional gain Kp
|
||
|
// Range of Kp is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->Kp, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// Proportaional gain Ki
|
||
|
// Range of Ki is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->Ki, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// Proportaional gain Kd
|
||
|
// Range of Kd is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->Kd, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CHTLoopSettingsPacketID());
|
||
|
|
||
|
}// encodeECU_CHTLoopSettingsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CHTLoopSettings packet
|
||
|
*
|
||
|
* Control loop settings for the CHT control loop
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CHTLoopSettingsPacketStructure(const void* _pg_pkt, ECU_CHTLoopSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CHTLoopSettingsPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_CHTLoopSettingsMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Filter value for derivative term
|
||
|
// Range of dTermFilter is 0 to 31.
|
||
|
_pg_user->dTermFilter = ((_pg_data[_pg_byteindex] >> 1) & 0x1F);
|
||
|
|
||
|
// CHT control loop enabled
|
||
|
_pg_user->enabled = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// Target CHT temperature
|
||
|
// Range of targetTemp is 0 to 255.
|
||
|
_pg_user->targetTemp = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Proportaional gain Kp
|
||
|
// Range of Kp is 0.0f to 65.535f.
|
||
|
_pg_user->Kp = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
// Proportaional gain Ki
|
||
|
// Range of Ki is 0.0f to 65.535f.
|
||
|
_pg_user->Ki = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
// Proportaional gain Kd
|
||
|
// Range of Kd is 0.0f to 65.535f.
|
||
|
_pg_user->Kd = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CHTLoopSettingsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CHTLoopSettings packet
|
||
|
*
|
||
|
* Control loop settings for the CHT control loop
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param dTermFilter is Filter value for derivative term
|
||
|
* \param enabled is CHT control loop enabled
|
||
|
* \param targetTemp is Target CHT temperature
|
||
|
* \param Kp is Proportaional gain Kp
|
||
|
* \param Ki is Proportaional gain Ki
|
||
|
* \param Kd is Proportaional gain Kd
|
||
|
*/
|
||
|
void encodeECU_CHTLoopSettingsPacket(void* _pg_pkt, uint8_t dTermFilter, bool enabled, uint8_t targetTemp, float Kp, float Ki, float Kd)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
_pg_data[_pg_byteindex] = 0;
|
||
|
|
||
|
// Filter value for derivative term
|
||
|
// Range of dTermFilter is 0 to 31.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(dTermFilter, 31) << 1;
|
||
|
|
||
|
// CHT control loop enabled
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)((enabled == true) ? 1 : 0);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// Target CHT temperature
|
||
|
// Range of targetTemp is 0 to 255.
|
||
|
uint8ToBytes(targetTemp, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Proportaional gain Kp
|
||
|
// Range of Kp is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(Kp, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// Proportaional gain Ki
|
||
|
// Range of Ki is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(Ki, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// Proportaional gain Kd
|
||
|
// Range of Kd is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(Kd, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CHTLoopSettingsPacketID());
|
||
|
|
||
|
}// encodeECU_CHTLoopSettingsPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CHTLoopSettings packet
|
||
|
*
|
||
|
* Control loop settings for the CHT control loop
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param dTermFilter receives Filter value for derivative term
|
||
|
* \param enabled receives CHT control loop enabled
|
||
|
* \param targetTemp receives Target CHT temperature
|
||
|
* \param Kp receives Proportaional gain Kp
|
||
|
* \param Ki receives Proportaional gain Ki
|
||
|
* \param Kd receives Proportaional gain Kd
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CHTLoopSettingsPacket(const void* _pg_pkt, uint8_t* dTermFilter, bool* enabled, uint8_t* targetTemp, float* Kp, float* Ki, float* Kd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CHTLoopSettingsPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_CHTLoopSettingsMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Filter value for derivative term
|
||
|
// Range of dTermFilter is 0 to 31.
|
||
|
(*dTermFilter) = ((_pg_data[_pg_byteindex] >> 1) & 0x1F);
|
||
|
|
||
|
// CHT control loop enabled
|
||
|
(*enabled) = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// Target CHT temperature
|
||
|
// Range of targetTemp is 0 to 255.
|
||
|
(*targetTemp) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Proportaional gain Kp
|
||
|
// Range of Kp is 0.0f to 65.535f.
|
||
|
(*Kp) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
// Proportaional gain Ki
|
||
|
// Range of Ki is 0.0f to 65.535f.
|
||
|
(*Ki) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
// Proportaional gain Kd
|
||
|
// Range of Kd is 0.0f to 65.535f.
|
||
|
(*Kd) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CHTLoopSettingsPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_DualPumpControlTelemetry packet
|
||
|
*
|
||
|
* Dual pump control telemetry. Send a zero-length packet with this identifier
|
||
|
* to the ECU to poll (request) this packet.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_DualPumpControlTelemetryPacketStructure(void* _pg_pkt, const ECU_DualPumpControlTelemetry_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
uint8ToBytes((uint8_t)(0xBB), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Current pump mode (which pump is running). Refer to the DualFuelPumpMode enumeration.
|
||
|
// Range of mode is 0 to 7.
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)limitMax(_pg_user->mode, 7) << 5;
|
||
|
|
||
|
// Current pump state machine state. Refer to the DualFuelPumpState enumeration.
|
||
|
// Range of state is 0 to 7.
|
||
|
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->state, 7) << 2;
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
|
||
|
// Time spent in current state
|
||
|
// Range of stateTimer is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->stateTimer, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPumpControlTelemetryPacketID());
|
||
|
|
||
|
}// encodeECU_DualPumpControlTelemetryPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_DualPumpControlTelemetry packet
|
||
|
*
|
||
|
* Dual pump control telemetry. Send a zero-length packet with this identifier
|
||
|
* to the ECU to poll (request) this packet.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_DualPumpControlTelemetryPacketStructure(const void* _pg_pkt, ECU_DualPumpControlTelemetry_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_DualPumpControlTelemetryPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_DualPumpControlTelemetryMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xBB)
|
||
|
return 0;
|
||
|
|
||
|
// Current pump mode (which pump is running). Refer to the DualFuelPumpMode enumeration.
|
||
|
// Range of mode is 0 to 7.
|
||
|
_pg_user->mode = (_pg_data[_pg_byteindex] >> 5);
|
||
|
|
||
|
// Current pump state machine state. Refer to the DualFuelPumpState enumeration.
|
||
|
// Range of state is 0 to 7.
|
||
|
_pg_user->state = ((_pg_data[_pg_byteindex] >> 2) & 0x7);
|
||
|
_pg_byteindex += 1; // close bit field
|
||
|
|
||
|
// Time spent in current state
|
||
|
// Range of stateTimer is 0 to 65535.
|
||
|
_pg_user->stateTimer = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_DualPumpControlTelemetryPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_DualPump_SetTelemetryPeriod packet
|
||
|
*
|
||
|
* Set the telemetry period for dual-pump messages
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param period is Telemetry period (0 = Off)
|
||
|
*/
|
||
|
void encodeECU_DualPump_SetTelemetryPeriodPacket(void* _pg_pkt, uint8_t period)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
uint8ToBytes((uint8_t)(0xBB), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Telemetry period (0 = Off)
|
||
|
// Range of period is 0 to 255.
|
||
|
uint8ToBytes(period, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPump_SetTelemetryPeriodPacketID());
|
||
|
|
||
|
}// encodeECU_DualPump_SetTelemetryPeriodPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_DualPump_SetTelemetryPeriod packet
|
||
|
*
|
||
|
* Set the telemetry period for dual-pump messages
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param period receives Telemetry period (0 = Off)
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_DualPump_SetTelemetryPeriodPacket(const void* _pg_pkt, uint8_t* period)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_DualPump_SetTelemetryPeriodPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_DualPump_SetTelemetryPeriodMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xBB)
|
||
|
return 0;
|
||
|
|
||
|
// Telemetry period (0 = Off)
|
||
|
// Range of period is 0 to 255.
|
||
|
(*period) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_DualPump_SetTelemetryPeriodPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_DualPump_SelectPump packet
|
||
|
*
|
||
|
* Command to manually select a given pump mode.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param pump is Pump selection (see DualFuelPumpMode enumeration)
|
||
|
*/
|
||
|
void encodeECU_DualPump_SelectPumpPacket(void* _pg_pkt, uint8_t pump)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
uint8ToBytes((uint8_t)(ECU_DUAL_PUMP_CMD_SET_PUMP), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Pump selection (see DualFuelPumpMode enumeration)
|
||
|
// Range of pump is 0 to 255.
|
||
|
uint8ToBytes(pump, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPump_SelectPumpPacketID());
|
||
|
|
||
|
}// encodeECU_DualPump_SelectPumpPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_DualPump_SelectPump packet
|
||
|
*
|
||
|
* Command to manually select a given pump mode.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param pump receives Pump selection (see DualFuelPumpMode enumeration)
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_DualPump_SelectPumpPacket(const void* _pg_pkt, uint8_t* pump)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_DualPump_SelectPumpPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_DualPump_SelectPumpMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC)
|
||
|
return 0;
|
||
|
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ECU_DUAL_PUMP_CMD_SET_PUMP)
|
||
|
return 0;
|
||
|
|
||
|
// Pump selection (see DualFuelPumpMode enumeration)
|
||
|
// Range of pump is 0 to 255.
|
||
|
(*pump) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_DualPump_SelectPumpPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_DualPump_TestPump packet
|
||
|
*
|
||
|
* Command to temporarily run a particular pump in test mode. ECU will revert
|
||
|
* to OTHER pump when test expires
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_DualPump_TestPumpPacketStructure(void* _pg_pkt, const ECU_DualPump_TestPump_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
uint8ToBytes((uint8_t)(ECU_DUAL_PUMP_CMD_TEST_PUMP), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Pump selection (see DualFuelPumpMode enumeration)
|
||
|
// Range of pump is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->pump, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Test timeout
|
||
|
// Range of timeout is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->timeout, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPump_TestPumpPacketID());
|
||
|
|
||
|
}// encodeECU_DualPump_TestPumpPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_DualPump_TestPump packet
|
||
|
*
|
||
|
* Command to temporarily run a particular pump in test mode. ECU will revert
|
||
|
* to OTHER pump when test expires
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_DualPump_TestPumpPacketStructure(const void* _pg_pkt, ECU_DualPump_TestPump_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_DualPump_TestPumpPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_DualPump_TestPumpMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// this packet has default fields, make sure they are set
|
||
|
_pg_user->timeout = 30;
|
||
|
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC)
|
||
|
return 0;
|
||
|
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ECU_DUAL_PUMP_CMD_TEST_PUMP)
|
||
|
return 0;
|
||
|
|
||
|
// Pump selection (see DualFuelPumpMode enumeration)
|
||
|
// Range of pump is 0 to 255.
|
||
|
_pg_user->pump = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
if(_pg_byteindex + 1 > _pg_numbytes)
|
||
|
return 1;
|
||
|
|
||
|
// Test timeout
|
||
|
// Range of timeout is 0 to 255.
|
||
|
_pg_user->timeout = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_DualPump_TestPumpPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ThrottleCalibration packet
|
||
|
*
|
||
|
* The throttle calibration packet sets the calibration values for minimum and
|
||
|
* maximum throttle position. The ECU uses these values to interpolate the
|
||
|
* throttle command.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_ThrottleCalibrationPacketStructure(void* _pg_pkt, const ECU_ThrottleSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned int _pg_tempbitfield = 0;
|
||
|
|
||
|
// Output position for 0% throttle in microseconds
|
||
|
// Range of pulseClosed is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->pulseClosed, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Output position for 100% throttle in microseconds
|
||
|
// Range of pulseOpen is 0 to 65535.
|
||
|
uint16ToBeBytes(_pg_user->pulseOpen, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle configuration settings
|
||
|
encodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config);
|
||
|
|
||
|
// Input PWM in microseconds for 0% throttle
|
||
|
// Range of pulseInputClosed is 0 to 4095.
|
||
|
_pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputClosed, 4095);
|
||
|
_pg_data[_pg_byteindex + 1] = (uint8_t)(_pg_tempbitfield << 4);
|
||
|
|
||
|
_pg_tempbitfield >>= 4;
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)_pg_tempbitfield;
|
||
|
|
||
|
|
||
|
// Input PWM in microseconds for 100% throttle
|
||
|
// Range of pulseInputOpen is 0 to 4095.
|
||
|
_pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputOpen, 4095);
|
||
|
_pg_data[_pg_byteindex + 2] = (uint8_t)_pg_tempbitfield;
|
||
|
|
||
|
_pg_tempbitfield >>= 8;
|
||
|
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_tempbitfield;
|
||
|
_pg_byteindex += 3; // close bit field
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCalibrationPacketID());
|
||
|
|
||
|
}// encodeECU_ThrottleCalibrationPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ThrottleCalibration packet
|
||
|
*
|
||
|
* The throttle calibration packet sets the calibration values for minimum and
|
||
|
* maximum throttle position. The ECU uses these values to interpolate the
|
||
|
* throttle command.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ThrottleCalibrationPacketStructure(const void* _pg_pkt, ECU_ThrottleSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
unsigned int _pg_tempbitfield = 0;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ThrottleCalibrationPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_ThrottleCalibrationMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Output position for 0% throttle in microseconds
|
||
|
// Range of pulseClosed is 0 to 65535.
|
||
|
_pg_user->pulseClosed = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Output position for 100% throttle in microseconds
|
||
|
// Range of pulseOpen is 0 to 65535.
|
||
|
_pg_user->pulseOpen = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle configuration settings
|
||
|
if(decodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config) == 0)
|
||
|
return 0;
|
||
|
|
||
|
// Input PWM in microseconds for 0% throttle
|
||
|
// Range of pulseInputClosed is 0 to 4095.
|
||
|
_pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xFF);
|
||
|
|
||
|
_pg_tempbitfield <<= 4;
|
||
|
_pg_tempbitfield |= (_pg_data[_pg_byteindex + 1] >> 4);
|
||
|
|
||
|
_pg_user->pulseInputClosed = _pg_tempbitfield;
|
||
|
|
||
|
// Input PWM in microseconds for 100% throttle
|
||
|
// Range of pulseInputOpen is 0 to 4095.
|
||
|
_pg_tempbitfield = (_pg_data[_pg_byteindex + 1] & 0xF);
|
||
|
|
||
|
_pg_tempbitfield <<= 8;
|
||
|
_pg_tempbitfield |= _pg_data[_pg_byteindex + 2];
|
||
|
|
||
|
_pg_user->pulseInputOpen = _pg_tempbitfield;
|
||
|
_pg_byteindex += 3; // close bit field
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ThrottleCalibrationPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ThrottleCalibration packet
|
||
|
*
|
||
|
* The throttle calibration packet sets the calibration values for minimum and
|
||
|
* maximum throttle position. The ECU uses these values to interpolate the
|
||
|
* throttle command.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param pulseClosed is Output position for 0% throttle in microseconds
|
||
|
* \param pulseOpen is Output position for 100% throttle in microseconds
|
||
|
* \param config is Throttle configuration settings
|
||
|
* \param pulseInputClosed is Input PWM in microseconds for 0% throttle
|
||
|
* \param pulseInputOpen is Input PWM in microseconds for 100% throttle
|
||
|
*/
|
||
|
void encodeECU_ThrottleCalibrationPacket(void* _pg_pkt, uint16_t pulseClosed, uint16_t pulseOpen, const ECU_ThrottleConfigBits_t* config, uint16_t pulseInputClosed, uint16_t pulseInputOpen)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned int _pg_tempbitfield = 0;
|
||
|
|
||
|
// Output position for 0% throttle in microseconds
|
||
|
// Range of pulseClosed is 0 to 65535.
|
||
|
uint16ToBeBytes(pulseClosed, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Output position for 100% throttle in microseconds
|
||
|
// Range of pulseOpen is 0 to 65535.
|
||
|
uint16ToBeBytes(pulseOpen, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle configuration settings
|
||
|
encodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, config);
|
||
|
|
||
|
// Input PWM in microseconds for 0% throttle
|
||
|
// Range of pulseInputClosed is 0 to 4095.
|
||
|
_pg_tempbitfield = (unsigned int)limitMax(pulseInputClosed, 4095);
|
||
|
_pg_data[_pg_byteindex + 1] = (uint8_t)(_pg_tempbitfield << 4);
|
||
|
|
||
|
_pg_tempbitfield >>= 4;
|
||
|
_pg_data[_pg_byteindex] = (uint8_t)_pg_tempbitfield;
|
||
|
|
||
|
// Input PWM in microseconds for 100% throttle
|
||
|
// Range of pulseInputOpen is 0 to 4095.
|
||
|
_pg_tempbitfield = (unsigned int)limitMax(pulseInputOpen, 4095);
|
||
|
_pg_data[_pg_byteindex + 2] = (uint8_t)_pg_tempbitfield;
|
||
|
|
||
|
_pg_tempbitfield >>= 8;
|
||
|
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_tempbitfield;
|
||
|
_pg_byteindex += 3; // close bit field
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCalibrationPacketID());
|
||
|
|
||
|
}// encodeECU_ThrottleCalibrationPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ThrottleCalibration packet
|
||
|
*
|
||
|
* The throttle calibration packet sets the calibration values for minimum and
|
||
|
* maximum throttle position. The ECU uses these values to interpolate the
|
||
|
* throttle command.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param pulseClosed receives Output position for 0% throttle in microseconds
|
||
|
* \param pulseOpen receives Output position for 100% throttle in microseconds
|
||
|
* \param config receives Throttle configuration settings
|
||
|
* \param pulseInputClosed receives Input PWM in microseconds for 0% throttle
|
||
|
* \param pulseInputOpen receives Input PWM in microseconds for 100% throttle
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ThrottleCalibrationPacket(const void* _pg_pkt, uint16_t* pulseClosed, uint16_t* pulseOpen, ECU_ThrottleConfigBits_t* config, uint16_t* pulseInputClosed, uint16_t* pulseInputOpen)
|
||
|
{
|
||
|
unsigned int _pg_tempbitfield = 0;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ThrottleCalibrationPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ThrottleCalibrationMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Output position for 0% throttle in microseconds
|
||
|
// Range of pulseClosed is 0 to 65535.
|
||
|
(*pulseClosed) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Output position for 100% throttle in microseconds
|
||
|
// Range of pulseOpen is 0 to 65535.
|
||
|
(*pulseOpen) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle configuration settings
|
||
|
if(decodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, config) == 0)
|
||
|
return 0;
|
||
|
|
||
|
// Input PWM in microseconds for 0% throttle
|
||
|
// Range of pulseInputClosed is 0 to 4095.
|
||
|
_pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xFF);
|
||
|
|
||
|
_pg_tempbitfield <<= 4;
|
||
|
_pg_tempbitfield |= (_pg_data[_pg_byteindex + 1] >> 4);
|
||
|
|
||
|
(*pulseInputClosed) = _pg_tempbitfield;
|
||
|
|
||
|
// Input PWM in microseconds for 100% throttle
|
||
|
// Range of pulseInputOpen is 0 to 4095.
|
||
|
_pg_tempbitfield = (_pg_data[_pg_byteindex + 1] & 0xF);
|
||
|
|
||
|
_pg_tempbitfield <<= 8;
|
||
|
_pg_tempbitfield |= _pg_data[_pg_byteindex + 2];
|
||
|
|
||
|
(*pulseInputOpen) = _pg_tempbitfield;
|
||
|
_pg_byteindex += 3; // close bit field
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ThrottleCalibrationPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_RPMLoopCalibration packet
|
||
|
*
|
||
|
* The RPM loop calibration packet controls the operating parameters of the RPM
|
||
|
* governor on the ECU. The control loop is implemented using a closed-loop PID
|
||
|
* controller with user-configurable proportional, integral, and derivative
|
||
|
* gains, and a gain scaler.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_RPMLoopCalibrationPacketStructure(void* _pg_pkt, const ECU_GovernorSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Proportaional feedback gain from normalized RPM error to throttle fraction
|
||
|
// Range of pGain is 0.0f to 6.5535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->pGain, _pg_data, &_pg_byteindex, 0.0f, 10000.0f);
|
||
|
|
||
|
// Integral feedback gain from normalized RPM error to throttle fraction
|
||
|
// Range of iGain is 0.0f to 6.5535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->iGain, _pg_data, &_pg_byteindex, 0.0f, 10000.0f);
|
||
|
|
||
|
// Derivative feedback gain from normalized RPM error to throttle fraction
|
||
|
// Range of dGain is 0.0f to 6.5535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->dGain, _pg_data, &_pg_byteindex, 0.0f, 10000.0f);
|
||
|
|
||
|
// Gain scaler power, positive numbers increase gain with RPM, and vice versa. User 0 to disable gain scaling
|
||
|
// Range of scalePower is -2.54f to 2.54f.
|
||
|
float32ScaledTo1SignedBytes(_pg_user->scalePower, _pg_data, &_pg_byteindex, 50.0f);
|
||
|
|
||
|
// Maximum commandable RPM
|
||
|
// Range of maxRPM is 0.0f to 25500.0f.
|
||
|
float32ScaledTo1UnsignedBytes(_pg_user->maxRPM, _pg_data, &_pg_byteindex, 0.0f, 0.01f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_RPMLoopCalibrationPacketID());
|
||
|
|
||
|
}// encodeECU_RPMLoopCalibrationPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_RPMLoopCalibration packet
|
||
|
*
|
||
|
* The RPM loop calibration packet controls the operating parameters of the RPM
|
||
|
* governor on the ECU. The control loop is implemented using a closed-loop PID
|
||
|
* controller with user-configurable proportional, integral, and derivative
|
||
|
* gains, and a gain scaler.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_RPMLoopCalibrationPacketStructure(const void* _pg_pkt, ECU_GovernorSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_RPMLoopCalibrationPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_RPMLoopCalibrationMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Proportaional feedback gain from normalized RPM error to throttle fraction
|
||
|
// Range of pGain is 0.0f to 6.5535f.
|
||
|
_pg_user->pGain = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10000.0f);
|
||
|
|
||
|
// Integral feedback gain from normalized RPM error to throttle fraction
|
||
|
// Range of iGain is 0.0f to 6.5535f.
|
||
|
_pg_user->iGain = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10000.0f);
|
||
|
|
||
|
// Derivative feedback gain from normalized RPM error to throttle fraction
|
||
|
// Range of dGain is 0.0f to 6.5535f.
|
||
|
_pg_user->dGain = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10000.0f);
|
||
|
|
||
|
// Gain scaler power, positive numbers increase gain with RPM, and vice versa. User 0 to disable gain scaling
|
||
|
// Range of scalePower is -2.54f to 2.54f.
|
||
|
_pg_user->scalePower = float32ScaledFrom1SignedBytes(_pg_data, &_pg_byteindex, 1.0f/50.0f);
|
||
|
|
||
|
// Maximum commandable RPM
|
||
|
// Range of maxRPM is 0.0f to 25500.0f.
|
||
|
_pg_user->maxRPM = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/0.01f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_RPMLoopCalibrationPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TPSDelayCalibration packet
|
||
|
*
|
||
|
* The throttle position delay configuration packet sends the desired throttle
|
||
|
* position delay (between 0 and 500ms) to the ECU, and also echoes back the
|
||
|
* TPS delay.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_TPSDelayCalibrationPacketStructure(void* _pg_pkt, const ECU_ThrottleSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Current TPS delay in seconds
|
||
|
// Range of delay is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->delay, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle delay configuration bits
|
||
|
encodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig);
|
||
|
|
||
|
// Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of maxDelay is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->maxDelay, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of minDelay is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->minDelay, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit)
|
||
|
// Range of softLimit is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->softLimit, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit
|
||
|
// Range of falloffRate is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->falloffRate, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU
|
||
|
// Range of throttleTarget is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->throttleTarget, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value
|
||
|
// Range of hardLimit is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->hardLimit, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TPSDelayCalibrationPacketID());
|
||
|
|
||
|
}// encodeECU_TPSDelayCalibrationPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TPSDelayCalibration packet
|
||
|
*
|
||
|
* The throttle position delay configuration packet sends the desired throttle
|
||
|
* position delay (between 0 and 500ms) to the ECU, and also echoes back the
|
||
|
* TPS delay.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TPSDelayCalibrationPacketStructure(const void* _pg_pkt, ECU_ThrottleSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TPSDelayCalibrationPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_TPSDelayCalibrationMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Current TPS delay in seconds
|
||
|
// Range of delay is 0 to 255.
|
||
|
_pg_user->delay = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle delay configuration bits
|
||
|
if(decodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig) == 0)
|
||
|
return 0;
|
||
|
|
||
|
// Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of maxDelay is 0 to 255.
|
||
|
_pg_user->maxDelay = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of minDelay is 0 to 255.
|
||
|
_pg_user->minDelay = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit)
|
||
|
// Range of softLimit is 0 to 255.
|
||
|
_pg_user->softLimit = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit
|
||
|
// Range of falloffRate is 0 to 255.
|
||
|
_pg_user->falloffRate = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU
|
||
|
// Range of throttleTarget is 0 to 255.
|
||
|
_pg_user->throttleTarget = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value
|
||
|
// Range of hardLimit is 0 to 255.
|
||
|
_pg_user->hardLimit = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TPSDelayCalibrationPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TPSDelayCalibration packet
|
||
|
*
|
||
|
* The throttle position delay configuration packet sends the desired throttle
|
||
|
* position delay (between 0 and 500ms) to the ECU, and also echoes back the
|
||
|
* TPS delay.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param delay is Current TPS delay in seconds
|
||
|
* \param delayConfig is Throttle delay configuration bits
|
||
|
* \param maxDelay is Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
* \param minDelay is Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
* \param softLimit is throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit)
|
||
|
* \param falloffRate is Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit
|
||
|
* \param throttleTarget is The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU
|
||
|
* \param hardLimit is This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value
|
||
|
*/
|
||
|
void encodeECU_TPSDelayCalibrationPacket(void* _pg_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)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Current TPS delay in seconds
|
||
|
// Range of delay is 0 to 255.
|
||
|
uint8ToBytes(delay, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle delay configuration bits
|
||
|
encodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, delayConfig);
|
||
|
|
||
|
// Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of maxDelay is 0 to 255.
|
||
|
uint8ToBytes(maxDelay, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of minDelay is 0 to 255.
|
||
|
uint8ToBytes(minDelay, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit)
|
||
|
// Range of softLimit is 0 to 255.
|
||
|
uint8ToBytes(softLimit, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit
|
||
|
// Range of falloffRate is 0 to 255.
|
||
|
uint8ToBytes(falloffRate, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU
|
||
|
// Range of throttleTarget is 0 to 255.
|
||
|
uint8ToBytes(throttleTarget, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value
|
||
|
// Range of hardLimit is 0 to 255.
|
||
|
uint8ToBytes(hardLimit, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TPSDelayCalibrationPacketID());
|
||
|
|
||
|
}// encodeECU_TPSDelayCalibrationPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TPSDelayCalibration packet
|
||
|
*
|
||
|
* The throttle position delay configuration packet sends the desired throttle
|
||
|
* position delay (between 0 and 500ms) to the ECU, and also echoes back the
|
||
|
* TPS delay.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param delay receives Current TPS delay in seconds
|
||
|
* \param delayConfig receives Throttle delay configuration bits
|
||
|
* \param maxDelay receives Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
* \param minDelay receives Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
* \param softLimit receives throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit)
|
||
|
* \param falloffRate receives Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit
|
||
|
* \param throttleTarget receives The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU
|
||
|
* \param hardLimit receives This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TPSDelayCalibrationPacket(const void* _pg_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)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TPSDelayCalibrationPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_TPSDelayCalibrationMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Current TPS delay in seconds
|
||
|
// Range of delay is 0 to 255.
|
||
|
(*delay) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle delay configuration bits
|
||
|
if(decodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, delayConfig) == 0)
|
||
|
return 0;
|
||
|
|
||
|
// Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of maxDelay is 0 to 255.
|
||
|
(*maxDelay) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting
|
||
|
// Range of minDelay is 0 to 255.
|
||
|
(*minDelay) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit)
|
||
|
// Range of softLimit is 0 to 255.
|
||
|
(*softLimit) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit
|
||
|
// Range of falloffRate is 0 to 255.
|
||
|
(*falloffRate) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU
|
||
|
// Range of throttleTarget is 0 to 255.
|
||
|
(*throttleTarget) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value
|
||
|
// Range of hardLimit is 0 to 255.
|
||
|
(*hardLimit) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TPSDelayCalibrationPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_TelemetrySettings packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_TelemetrySettingsPacketStructure(void* _pg_pkt, const ECU_TelemetrySettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Time between fast telemetry packets in 50ms increments
|
||
|
// Range of fastTelemetryPeriod is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->fastTelemetryPeriod, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Time between slow telemetry packets in 500ms increments
|
||
|
// Range of slowTelemetryPeriod is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->slowTelemetryPeriod, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Seconds of time the ECU waits after bootup before sending telemetry.
|
||
|
// Range of silencePeriod is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->silencePeriod, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySettingsPacketID());
|
||
|
|
||
|
}// encodeECU_TelemetrySettingsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_TelemetrySettings packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_TelemetrySettingsPacketStructure(const void* _pg_pkt, ECU_TelemetrySettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_TelemetrySettingsPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_TelemetrySettingsMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Time between fast telemetry packets in 50ms increments
|
||
|
// Range of fastTelemetryPeriod is 0 to 255.
|
||
|
_pg_user->fastTelemetryPeriod = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Time between slow telemetry packets in 500ms increments
|
||
|
// Range of slowTelemetryPeriod is 0 to 255.
|
||
|
_pg_user->slowTelemetryPeriod = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Seconds of time the ECU waits after bootup before sending telemetry.
|
||
|
// Range of silencePeriod is 0 to 255.
|
||
|
_pg_user->silencePeriod = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_TelemetrySettingsPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_PumpConfig packet
|
||
|
*
|
||
|
* The pump config packet is sent to the ECU to configure fuel pump control
|
||
|
* loop parameters. The ECU will echo the packet as confirmation of its
|
||
|
* receipt. Send a zero length packet to request the current settings. Note
|
||
|
* that the fuel pump configuration consists of two packets, this one and
|
||
|
* Pump2config.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_PumpConfigPacketStructure(void* _pg_pkt, const ECU_PumpSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Fuel pump proportional gain
|
||
|
// Range of kp is 0.0f to 655.35f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->kp, _pg_data, &_pg_byteindex, 0.0f, 100.0f);
|
||
|
|
||
|
// Pump low pressure limit in kilo-Pascals
|
||
|
// Range of pressureLowerLimit is 0.0f to 4518.40871f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->pressureLowerLimit, _pg_data, &_pg_byteindex, 0.0f, 14.504f);
|
||
|
|
||
|
// Pump high pressure limit in kilo-Pascals
|
||
|
// Range of pressureUpperLimit is 0.0f to 4518.40871f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->pressureUpperLimit, _pg_data, &_pg_byteindex, 0.0f, 14.504f);
|
||
|
|
||
|
// Pump pressure setpoint in kilo-Pascals
|
||
|
// Range of pressureSetpoint is 0.0f to 4518.40871f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->pressureSetpoint, _pg_data, &_pg_byteindex, 0.0f, 14.504f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PumpConfigPacketID());
|
||
|
|
||
|
}// encodeECU_PumpConfigPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_PumpConfig packet
|
||
|
*
|
||
|
* The pump config packet is sent to the ECU to configure fuel pump control
|
||
|
* loop parameters. The ECU will echo the packet as confirmation of its
|
||
|
* receipt. Send a zero length packet to request the current settings. Note
|
||
|
* that the fuel pump configuration consists of two packets, this one and
|
||
|
* Pump2config.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_PumpConfigPacketStructure(const void* _pg_pkt, ECU_PumpSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_PumpConfigPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_PumpConfigMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Fuel pump proportional gain
|
||
|
// Range of kp is 0.0f to 655.35f.
|
||
|
_pg_user->kp = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/100.0f);
|
||
|
|
||
|
// Pump low pressure limit in kilo-Pascals
|
||
|
// Range of pressureLowerLimit is 0.0f to 4518.40871f.
|
||
|
_pg_user->pressureLowerLimit = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/14.504f);
|
||
|
|
||
|
// Pump high pressure limit in kilo-Pascals
|
||
|
// Range of pressureUpperLimit is 0.0f to 4518.40871f.
|
||
|
_pg_user->pressureUpperLimit = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/14.504f);
|
||
|
|
||
|
// Pump pressure setpoint in kilo-Pascals
|
||
|
// Range of pressureSetpoint is 0.0f to 4518.40871f.
|
||
|
_pg_user->pressureSetpoint = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/14.504f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_PumpConfigPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_Pump2Config packet
|
||
|
*
|
||
|
* The pump 2 config packet is used for further configuration of pump
|
||
|
* operation. This packet allows the user to configure integral gain values and
|
||
|
* PWM limits. The ECU will echo the packet as confirmation of its receipt.
|
||
|
* Send a zero length packet to request the current settings.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_Pump2ConfigPacketStructure(void* _pg_pkt, const ECU_PumpSettings_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// Fuel pump integral gain
|
||
|
// Range of ki is 0.0f to 65.535f.
|
||
|
float32ScaledTo2UnsignedBeBytes(_pg_user->ki, _pg_data, &_pg_byteindex, 0.0f, 1000.0f);
|
||
|
|
||
|
// Minimum duty cycle in percent (250 = 100%)
|
||
|
// Range of minimumPWM is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->minimumPWM, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Maximum duty cycle in percent (250 = 100%)
|
||
|
// Range of maximumPWM is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->maximumPWM, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Reserved for future use
|
||
|
uint16ToBeBytes((uint16_t)(0), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Pump duty cycle ramp rate
|
||
|
// Range of rampRate is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->rampRate, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_Pump2ConfigPacketID());
|
||
|
|
||
|
}// encodeECU_Pump2ConfigPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_Pump2Config packet
|
||
|
*
|
||
|
* The pump 2 config packet is used for further configuration of pump
|
||
|
* operation. This packet allows the user to configure integral gain values and
|
||
|
* PWM limits. The ECU will echo the packet as confirmation of its receipt.
|
||
|
* Send a zero length packet to request the current settings.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_Pump2ConfigPacketStructure(const void* _pg_pkt, ECU_PumpSettings_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_Pump2ConfigPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_Pump2ConfigMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// Fuel pump integral gain
|
||
|
// Range of ki is 0.0f to 65.535f.
|
||
|
_pg_user->ki = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f);
|
||
|
|
||
|
// Minimum duty cycle in percent (250 = 100%)
|
||
|
// Range of minimumPWM is 0 to 255.
|
||
|
_pg_user->minimumPWM = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Maximum duty cycle in percent (250 = 100%)
|
||
|
// Range of maximumPWM is 0 to 255.
|
||
|
_pg_user->maximumPWM = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Reserved for future use
|
||
|
_pg_byteindex += 2;
|
||
|
|
||
|
// Pump duty cycle ramp rate
|
||
|
// Range of rampRate is 0 to 255.
|
||
|
_pg_user->rampRate = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_Pump2ConfigPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_UserData packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param userData is 8 bytes of user data
|
||
|
*/
|
||
|
void encodeECU_UserDataPacket(void* _pg_pkt, const uint8_t userData[8])
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned _pg_i = 0;
|
||
|
|
||
|
// 8 bytes of user data
|
||
|
// Range of userData is 0 to 255.
|
||
|
for(_pg_i = 0; _pg_i < 8; _pg_i++)
|
||
|
uint8ToBytes(userData[_pg_i], _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_UserDataPacketID());
|
||
|
|
||
|
}// encodeECU_UserDataPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_UserData packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param userData receives 8 bytes of user data
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_UserDataPacket(const void* _pg_pkt, uint8_t userData[8])
|
||
|
{
|
||
|
unsigned _pg_i = 0;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_UserDataPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_UserDataMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// 8 bytes of user data
|
||
|
// Range of userData is 0 to 255.
|
||
|
for(_pg_i = 0; _pg_i < 8; _pg_i++)
|
||
|
userData[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_UserDataPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ThrottleCurve packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param throttleCurve is Throttle output values for the lower 6 cells in the throttle lookup table
|
||
|
*/
|
||
|
void encodeECU_ThrottleCurvePacket(void* _pg_pkt, const float throttleCurve[6])
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned _pg_i = 0;
|
||
|
|
||
|
// Throttle output values for the lower 6 cells in the throttle lookup table
|
||
|
// Range of throttleCurve is 0.0f to 127.5f.
|
||
|
for(_pg_i = 0; _pg_i < 6; _pg_i++)
|
||
|
float32ScaledTo1UnsignedBytes(throttleCurve[_pg_i], _pg_data, &_pg_byteindex, 0.0f, 2.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCurvePacketID());
|
||
|
|
||
|
}// encodeECU_ThrottleCurvePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ThrottleCurve packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param throttleCurve receives Throttle output values for the lower 6 cells in the throttle lookup table
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ThrottleCurvePacket(const void* _pg_pkt, float throttleCurve[6])
|
||
|
{
|
||
|
unsigned _pg_i = 0;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ThrottleCurvePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ThrottleCurveMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Throttle output values for the lower 6 cells in the throttle lookup table
|
||
|
// Range of throttleCurve is 0.0f to 127.5f.
|
||
|
for(_pg_i = 0; _pg_i < 6; _pg_i++)
|
||
|
throttleCurve[_pg_i] = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ThrottleCurvePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ThrottleCurve1 packet
|
||
|
*
|
||
|
* Second throttle curve packet, which contains the upper 5 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param throttleCurve is Throttle output values for the upper 5 cells in the throttle lookup table
|
||
|
*/
|
||
|
void encodeECU_ThrottleCurve1Packet(void* _pg_pkt, const float throttleCurve[5])
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned _pg_i = 0;
|
||
|
|
||
|
// Throttle output values for the upper 5 cells in the throttle lookup table
|
||
|
// Range of throttleCurve is 0.0f to 127.5f.
|
||
|
for(_pg_i = 0; _pg_i < 5; _pg_i++)
|
||
|
float32ScaledTo1UnsignedBytes(throttleCurve[_pg_i], _pg_data, &_pg_byteindex, 0.0f, 2.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCurve1PacketID());
|
||
|
|
||
|
}// encodeECU_ThrottleCurve1Packet
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ThrottleCurve1 packet
|
||
|
*
|
||
|
* Second throttle curve packet, which contains the upper 5 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param throttleCurve receives Throttle output values for the upper 5 cells in the throttle lookup table
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ThrottleCurve1Packet(const void* _pg_pkt, float throttleCurve[5])
|
||
|
{
|
||
|
unsigned _pg_i = 0;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ThrottleCurve1PacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ThrottleCurve1MinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// Throttle output values for the upper 5 cells in the throttle lookup table
|
||
|
// Range of throttleCurve is 0.0f to 127.5f.
|
||
|
for(_pg_i = 0; _pg_i < 5; _pg_i++)
|
||
|
throttleCurve[_pg_i] = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ThrottleCurve1Packet
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SystemCommand packet
|
||
|
*
|
||
|
* The system command packets follow the format provided below. Refer further
|
||
|
* in the document for complete documentation on each system command packet.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param _pg_user points to the user data that will be encoded in _pg_pkt
|
||
|
*/
|
||
|
void encodeECU_SystemCommandPacketStructure(void* _pg_pkt, const ECU_SystemCommand_t* _pg_user)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
unsigned _pg_i = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
uint8ToBytes(_pg_user->cmd, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Up to 3 parameter bytes for a system command
|
||
|
// Range of parambytes is 0 to 255.
|
||
|
for(_pg_i = 0; _pg_i < 3; _pg_i++)
|
||
|
uint8ToBytes(_pg_user->parambytes[_pg_i], _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SystemCommandPacketID());
|
||
|
|
||
|
}// encodeECU_SystemCommandPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SystemCommand packet
|
||
|
*
|
||
|
* The system command packets follow the format provided below. Refer further
|
||
|
* in the document for complete documentation on each system command packet.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param _pg_user receives the data decoded from the packet
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SystemCommandPacketStructure(const void* _pg_pkt, ECU_SystemCommand_t* _pg_user)
|
||
|
{
|
||
|
int _pg_numbytes;
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data;
|
||
|
unsigned _pg_i = 0;
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SystemCommandPacketID())
|
||
|
return 0;
|
||
|
|
||
|
// Verify the packet size
|
||
|
_pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
if(_pg_numbytes < getECU_SystemCommandMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The raw data from the packet
|
||
|
_pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
|
||
|
// this packet has default fields, make sure they are set
|
||
|
for(_pg_i = 0; _pg_i < 3; _pg_i++)
|
||
|
_pg_user->parambytes[_pg_i] = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
_pg_user->cmd = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
if(_pg_byteindex + 1*3 > _pg_numbytes)
|
||
|
return 1;
|
||
|
|
||
|
// Up to 3 parameter bytes for a system command
|
||
|
// Range of parambytes is 0 to 255.
|
||
|
for(_pg_i = 0; _pg_i < 3; _pg_i++)
|
||
|
_pg_user->parambytes[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SystemCommandPacketStructure
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CalibrateAnalogClosed packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_CalibrateAnalogClosedPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_ANALOG_CLOSED), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibrateAnalogClosedPacketID());
|
||
|
|
||
|
}// encodeECU_CalibrateAnalogClosedPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CalibrateAnalogClosed packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CalibrateAnalogClosedPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CalibrateAnalogClosedPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_CalibrateAnalogClosedMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_CALIBRATE_ANALOG_CLOSED
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_CALIBRATE_ANALOG_CLOSED)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CalibrateAnalogClosedPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CalibrateAnalogOpen packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_CalibrateAnalogOpenPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_ANALOG_OPEN), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibrateAnalogOpenPacketID());
|
||
|
|
||
|
}// encodeECU_CalibrateAnalogOpenPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CalibrateAnalogOpen packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CalibrateAnalogOpenPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CalibrateAnalogOpenPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_CalibrateAnalogOpenMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_CALIBRATE_ANALOG_OPEN
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_CALIBRATE_ANALOG_OPEN)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CalibrateAnalogOpenPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CalibratePulseClosed packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_CalibratePulseClosedPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_PULSE_CLOSED), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibratePulseClosedPacketID());
|
||
|
|
||
|
}// encodeECU_CalibratePulseClosedPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CalibratePulseClosed packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CalibratePulseClosedPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CalibratePulseClosedPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_CalibratePulseClosedMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_CALIBRATE_PULSE_CLOSED
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_CALIBRATE_PULSE_CLOSED)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CalibratePulseClosedPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CalibratePulseOpen packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_CalibratePulseOpenPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_PULSE_OPEN), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibratePulseOpenPacketID());
|
||
|
|
||
|
}// encodeECU_CalibratePulseOpenPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CalibratePulseOpen packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CalibratePulseOpenPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CalibratePulseOpenPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_CalibratePulseOpenMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_CALIBRATE_PULSE_OPEN
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_CALIBRATE_PULSE_OPEN)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CalibratePulseOpenPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_CalibratePulseWrite packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_CalibratePulseWritePacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_PULSE_WRITE), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibratePulseWritePacketID());
|
||
|
|
||
|
}// encodeECU_CalibratePulseWritePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_CalibratePulseWrite packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_CalibratePulseWritePacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_CalibratePulseWritePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_CalibratePulseWriteMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_CALIBRATE_PULSE_WRITE
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_CALIBRATE_PULSE_WRITE)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_CalibratePulseWritePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetOutputDriver packet
|
||
|
*
|
||
|
* Set one of four high-current output drivers.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param driver is Select driver number (1, 2, 3 or 4)
|
||
|
* \param status is Set driver status (1 = ON, 0 = OFF)
|
||
|
*/
|
||
|
void encodeECU_SetOutputDriverPacket(void* _pg_pkt, uint8_t driver, uint8_t status)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_OUTPUT_DRIVER), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Select driver number (1, 2, 3 or 4)
|
||
|
// Range of driver is 0 to 255.
|
||
|
uint8ToBytes(driver, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Set driver status (1 = ON, 0 = OFF)
|
||
|
// Range of status is 0 to 255.
|
||
|
uint8ToBytes(status, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetOutputDriverPacketID());
|
||
|
|
||
|
}// encodeECU_SetOutputDriverPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetOutputDriver packet
|
||
|
*
|
||
|
* Set one of four high-current output drivers.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param driver receives Select driver number (1, 2, 3 or 4)
|
||
|
* \param status receives Set driver status (1 = ON, 0 = OFF)
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetOutputDriverPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* driver, uint8_t* status)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetOutputDriverPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetOutputDriverMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_OUTPUT_DRIVER
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_OUTPUT_DRIVER)
|
||
|
return 0;
|
||
|
|
||
|
// Select driver number (1, 2, 3 or 4)
|
||
|
// Range of driver is 0 to 255.
|
||
|
(*driver) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Set driver status (1 = ON, 0 = OFF)
|
||
|
// Range of status is 0 to 255.
|
||
|
(*status) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetOutputDriverPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetThrottleCurveActive packet
|
||
|
*
|
||
|
* Turn the throttle linearization curve either on or off.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param active is Curve active (1 = ON, 0 = OFF)
|
||
|
*/
|
||
|
void encodeECU_SetThrottleCurveActivePacket(void* _pg_pkt, uint8_t active)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_THROTTLE_CURVE_ACTIVE), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Curve active (1 = ON, 0 = OFF)
|
||
|
// Range of active is 0 to 255.
|
||
|
uint8ToBytes(active, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetThrottleCurveActivePacketID());
|
||
|
|
||
|
}// encodeECU_SetThrottleCurveActivePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetThrottleCurveActive packet
|
||
|
*
|
||
|
* Turn the throttle linearization curve either on or off.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param active receives Curve active (1 = ON, 0 = OFF)
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetThrottleCurveActivePacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* active)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetThrottleCurveActivePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetThrottleCurveActiveMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_THROTTLE_CURVE_ACTIVE
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_THROTTLE_CURVE_ACTIVE)
|
||
|
return 0;
|
||
|
|
||
|
// Curve active (1 = ON, 0 = OFF)
|
||
|
// Range of active is 0 to 255.
|
||
|
(*active) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetThrottleCurveActivePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetThrottleCurveElement packet
|
||
|
*
|
||
|
* Set individual elements in the throttle linearization lookup table.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param index is Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input
|
||
|
* \param throttleOutput is Percentage throttle output for this curve element
|
||
|
*/
|
||
|
void encodeECU_SetThrottleCurveElementPacket(void* _pg_pkt, uint8_t index, float throttleOutput)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_THROTTLE_CURVE_ELEMENT), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input
|
||
|
// Range of index is 0 to 255.
|
||
|
uint8ToBytes(index, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Percentage throttle output for this curve element
|
||
|
// Range of throttleOutput is 0.0f to 127.5f.
|
||
|
float32ScaledTo1UnsignedBytes(throttleOutput, _pg_data, &_pg_byteindex, 0.0f, 2.0f);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetThrottleCurveElementPacketID());
|
||
|
|
||
|
}// encodeECU_SetThrottleCurveElementPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetThrottleCurveElement packet
|
||
|
*
|
||
|
* Set individual elements in the throttle linearization lookup table.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param index receives Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input
|
||
|
* \param throttleOutput receives Percentage throttle output for this curve element
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetThrottleCurveElementPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* index, float* throttleOutput)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetThrottleCurveElementPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetThrottleCurveElementMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_THROTTLE_CURVE_ELEMENT
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_THROTTLE_CURVE_ELEMENT)
|
||
|
return 0;
|
||
|
|
||
|
// Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input
|
||
|
// Range of index is 0 to 255.
|
||
|
(*index) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Percentage throttle output for this curve element
|
||
|
// Range of throttleOutput is 0.0f to 127.5f.
|
||
|
(*throttleOutput) = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetThrottleCurveElementPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_RequestThrottleCurveData packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_RequestThrottleCurveDataPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_REQUEST_THROTTLE_CURVE_DATA), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_RequestThrottleCurveDataPacketID());
|
||
|
|
||
|
}// encodeECU_RequestThrottleCurveDataPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_RequestThrottleCurveData packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_RequestThrottleCurveDataPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_RequestThrottleCurveDataPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_RequestThrottleCurveDataMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_REQUEST_THROTTLE_CURVE_DATA
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_REQUEST_THROTTLE_CURVE_DATA)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_RequestThrottleCurveDataPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ResetFuelUsed packet
|
||
|
*
|
||
|
* Reset the FuelUsed value. This will set the FuelUsed data to zero.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_ResetFuelUsedPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_RESET_FUEL_USED), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ResetFuelUsedPacketID());
|
||
|
|
||
|
}// encodeECU_ResetFuelUsedPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ResetFuelUsed packet
|
||
|
*
|
||
|
* Reset the FuelUsed value. This will set the FuelUsed data to zero.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ResetFuelUsedPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ResetFuelUsedPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ResetFuelUsedMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_RESET_FUEL_USED
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_RESET_FUEL_USED)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ResetFuelUsedPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetFuelUsedDivisor packet
|
||
|
*
|
||
|
* Set the fuel used divisor
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param divisor is 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).
|
||
|
*/
|
||
|
void encodeECU_SetFuelUsedDivisorPacket(void* _pg_pkt, uint16_t divisor)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_FUEL_USED_DIVISOR), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// 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).
|
||
|
// Range of divisor is 0 to 65535.
|
||
|
uint16ToBeBytes(divisor, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetFuelUsedDivisorPacketID());
|
||
|
|
||
|
}// encodeECU_SetFuelUsedDivisorPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetFuelUsedDivisor packet
|
||
|
*
|
||
|
* Set the fuel used divisor
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param divisor receives 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).
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetFuelUsedDivisorPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint16_t* divisor)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetFuelUsedDivisorPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetFuelUsedDivisorMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_FUEL_USED_DIVISOR
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_FUEL_USED_DIVISOR)
|
||
|
return 0;
|
||
|
|
||
|
// 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).
|
||
|
// Range of divisor is 0 to 65535.
|
||
|
(*divisor) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetFuelUsedDivisorPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetFuelUsedResetFlag packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param reset is 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up
|
||
|
*/
|
||
|
void encodeECU_SetFuelUsedResetFlagPacket(void* _pg_pkt, uint8_t reset)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_FUEL_USED_RESET_ON_STARTUP), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up
|
||
|
// Range of reset is 0 to 255.
|
||
|
uint8ToBytes(reset, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetFuelUsedResetFlagPacketID());
|
||
|
|
||
|
}// encodeECU_SetFuelUsedResetFlagPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetFuelUsedResetFlag packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param reset receives 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetFuelUsedResetFlagPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* reset)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetFuelUsedResetFlagPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetFuelUsedResetFlagMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_FUEL_USED_RESET_ON_STARTUP
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_FUEL_USED_RESET_ON_STARTUP)
|
||
|
return 0;
|
||
|
|
||
|
// 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up
|
||
|
// Range of reset is 0 to 255.
|
||
|
(*reset) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetFuelUsedResetFlagPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetGovernorMode packet
|
||
|
*
|
||
|
* Manually set the RPM governor mode.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param mode is MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command
|
||
|
*/
|
||
|
void encodeECU_SetGovernorModePacket(void* _pg_pkt, ECUGovernorMode mode)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_GOVERNOR_MODE), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command
|
||
|
// Range of mode is 0 to 255.
|
||
|
uint8ToBytes(mode, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetGovernorModePacketID());
|
||
|
|
||
|
}// encodeECU_SetGovernorModePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetGovernorMode packet
|
||
|
*
|
||
|
* Manually set the RPM governor mode.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param mode receives MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetGovernorModePacket(const void* _pg_pkt, ECUSystemCommands* cmd, ECUGovernorMode* mode)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetGovernorModePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetGovernorModeMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_GOVERNOR_MODE
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_GOVERNOR_MODE)
|
||
|
return 0;
|
||
|
|
||
|
// MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command
|
||
|
// Range of mode is 0 to 255.
|
||
|
(*mode) = (ECUGovernorMode)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetGovernorModePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetSerialMode packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param mode is The serial relay mode to command
|
||
|
*/
|
||
|
void encodeECU_SetSerialModePacket(void* _pg_pkt, ECUAutronicRelayState mode)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_SERIAL_MODE), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The serial relay mode to command
|
||
|
// Range of mode is 0 to 255.
|
||
|
uint8ToBytes(mode, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetSerialModePacketID());
|
||
|
|
||
|
}// encodeECU_SetSerialModePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetSerialMode packet
|
||
|
*
|
||
|
* 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.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param mode receives The serial relay mode to command
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetSerialModePacket(const void* _pg_pkt, ECUSystemCommands* cmd, ECUAutronicRelayState* mode)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetSerialModePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetSerialModeMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_SERIAL_MODE
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_SERIAL_MODE)
|
||
|
return 0;
|
||
|
|
||
|
// The serial relay mode to command
|
||
|
// Range of mode is 0 to 255.
|
||
|
(*mode) = (ECUAutronicRelayState)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetSerialModePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetECUAddress packet
|
||
|
*
|
||
|
* Set a custom address value for the ECU.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param address is ECU address in the range {1, 65534}
|
||
|
*/
|
||
|
void encodeECU_SetECUAddressPacket(void* _pg_pkt, uint16_t address)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_NODE_ID), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// ECU address in the range {1, 65534}
|
||
|
// Range of address is 0 to 65535.
|
||
|
uint16ToBeBytes(address, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetECUAddressPacketID());
|
||
|
|
||
|
}// encodeECU_SetECUAddressPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetECUAddress packet
|
||
|
*
|
||
|
* Set a custom address value for the ECU.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param address receives ECU address in the range {1, 65534}
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetECUAddressPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint16_t* address)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetECUAddressPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetECUAddressMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_NODE_ID
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_NODE_ID)
|
||
|
return 0;
|
||
|
|
||
|
// ECU address in the range {1, 65534}
|
||
|
// Range of address is 0 to 65535.
|
||
|
(*address) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetECUAddressPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_SetUserData packet
|
||
|
*
|
||
|
* Save a single byte of USER_DATA in EEPROM.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param index is USER_DATA address (0 to 7)
|
||
|
* \param userdata is USER_DATA variable
|
||
|
*/
|
||
|
void encodeECU_SetUserDataPacket(void* _pg_pkt, uint8_t index, uint8_t userdata)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_SET_USER_DATA), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// USER_DATA address (0 to 7)
|
||
|
// Range of index is 0 to 255.
|
||
|
uint8ToBytes(index, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// USER_DATA variable
|
||
|
// Range of userdata is 0 to 255.
|
||
|
uint8ToBytes(userdata, _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetUserDataPacketID());
|
||
|
|
||
|
}// encodeECU_SetUserDataPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_SetUserData packet
|
||
|
*
|
||
|
* Save a single byte of USER_DATA in EEPROM.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param index receives USER_DATA address (0 to 7)
|
||
|
* \param userdata receives USER_DATA variable
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_SetUserDataPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* index, uint8_t* userdata)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_SetUserDataPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_SetUserDataMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_SET_USER_DATA
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_SET_USER_DATA)
|
||
|
return 0;
|
||
|
|
||
|
// USER_DATA address (0 to 7)
|
||
|
// Range of index is 0 to 255.
|
||
|
(*index) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
// USER_DATA variable
|
||
|
// Range of userdata is 0 to 255.
|
||
|
(*userdata) = uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_SetUserDataPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ResetEngineTime packet
|
||
|
*
|
||
|
* Reset the engine runtime.
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
* \param time is The new value of the engine time counter in seconds
|
||
|
*/
|
||
|
void encodeECU_ResetEngineTimePacket(void* _pg_pkt, uint32_t time)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_RESET_ENGINE_TIME), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// The new value of the engine time counter in seconds
|
||
|
// Range of time is 0 to 16777215.
|
||
|
uint24ToBeBytes((uint32_t)(limitMax(time, 16777215)), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ResetEngineTimePacketID());
|
||
|
|
||
|
}// encodeECU_ResetEngineTimePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ResetEngineTime packet
|
||
|
*
|
||
|
* Reset the engine runtime.
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \param time receives The new value of the engine time counter in seconds
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ResetEngineTimePacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint32_t* time)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ResetEngineTimePacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ResetEngineTimeMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// this packet has default fields, make sure they are set
|
||
|
(*time) = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_RESET_ENGINE_TIME
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_RESET_ENGINE_TIME)
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_byteindex + 3 > _pg_numbytes)
|
||
|
return 1;
|
||
|
|
||
|
// The new value of the engine time counter in seconds
|
||
|
// Range of time is 0 to 16777215.
|
||
|
(*time) = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex);
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ResetEngineTimePacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Create the ECU_ResetECU packet
|
||
|
*
|
||
|
* Reset the ECU
|
||
|
* \param _pg_pkt points to the packet which will be created by this function
|
||
|
*/
|
||
|
void encodeECU_ResetECUPacket(void* _pg_pkt)
|
||
|
{
|
||
|
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
|
||
|
int _pg_byteindex = 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
uint8ToBytes((uint8_t)(CMD_ECU_RESET_ECU), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Required constant value
|
||
|
uint8ToBytes((uint8_t)(0xA5), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Required constant value
|
||
|
uint8ToBytes((uint8_t)(0x5A), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// Required constant value
|
||
|
uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex);
|
||
|
|
||
|
// complete the process of creating the packet
|
||
|
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ResetECUPacketID());
|
||
|
|
||
|
}// encodeECU_ResetECUPacket
|
||
|
|
||
|
/*!
|
||
|
* \brief Decode the ECU_ResetECU packet
|
||
|
*
|
||
|
* Reset the ECU
|
||
|
* \param _pg_pkt points to the packet being decoded by this function
|
||
|
* \param cmd receives The command enumeration
|
||
|
* \return 0 is returned if the packet ID or size is wrong, else 1
|
||
|
*/
|
||
|
int decodeECU_ResetECUPacket(const void* _pg_pkt, ECUSystemCommands* cmd)
|
||
|
{
|
||
|
int _pg_byteindex = 0;
|
||
|
const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt);
|
||
|
int _pg_numbytes = getECUPacketSize(_pg_pkt);
|
||
|
|
||
|
// Verify the packet identifier
|
||
|
if(getECUPacketID(_pg_pkt) != getECU_ResetECUPacketID())
|
||
|
return 0;
|
||
|
|
||
|
if(_pg_numbytes < getECU_ResetECUMinDataLength())
|
||
|
return 0;
|
||
|
|
||
|
// The command enumeration
|
||
|
// Range of cmd is 0 to 255.
|
||
|
// Decoded value must be CMD_ECU_RESET_ECU
|
||
|
(*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex);
|
||
|
if ((*cmd) != CMD_ECU_RESET_ECU)
|
||
|
return 0;
|
||
|
|
||
|
// Required constant value
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xA5)
|
||
|
return 0;
|
||
|
|
||
|
// Required constant value
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x5A)
|
||
|
return 0;
|
||
|
|
||
|
// Required constant value
|
||
|
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC)
|
||
|
return 0;
|
||
|
|
||
|
return 1;
|
||
|
|
||
|
}// decodeECU_ResetECUPacket
|
||
|
// end of ECUPackets.c
|