AP_PiccoloCAN: Add Currawong ECU piccolo protocol

This commit is contained in:
Reilly Callaway 2022-03-30 14:23:39 +11:00 committed by Peter Barker
parent 9a71da2742
commit 813c21ffc0
10 changed files with 7440 additions and 0 deletions

View File

@ -1059,4 +1059,71 @@ uint32_t getServoPacketID(const void* pkt)
return (uint32_t) ((frame->id >> 16) & 0xFF);
}
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getECUPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getECUPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishECUPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x09mmdddd
* - 07 = ECU_IN (to and ECU) group ID
* - mm = Message ID
* - dd = Device ID
*
* Note: The Device ID (lower 16 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) AP_PiccoloCAN::MessageGroup::ECU_IN) << 24) | // CAN Group ID
((packetID & 0xFF) << 16); // Message ID
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getECUPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getECUPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}
#endif // HAL_PICCOLO_CAN_ENABLE

View File

@ -0,0 +1,663 @@
// ECUDefines.c was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "ECUDefines.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Encode a ECU_AuxiliaryErrorBits_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_AuxiliaryErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_AuxiliaryErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 if CAN servo is not connected
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->servoLink == true) ? 1 : 0) << 7;
// 1 if CAN servo is reporting a position error
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->servoPosition == true) ? 1 : 0) << 6;
// Reserved for future use
// Range of reserved_A is 0 to 63.
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reserved_A;
// Reserved for future use
// Range of reserved_B is 0 to 255.
_pg_data[_pg_byteindex + 1] = (uint8_t)_pg_user->reserved_B;
// Reserved for future use
// Range of reserved_C is 0 to 255.
_pg_data[_pg_byteindex + 2] = (uint8_t)_pg_user->reserved_C;
// Reserved for future use
// Range of reserved_D is 0 to 255.
_pg_data[_pg_byteindex + 3] = (uint8_t)_pg_user->reserved_D;
_pg_byteindex += 4; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeECU_AuxiliaryErrorBits_t
/*!
* \brief Decode a ECU_AuxiliaryErrorBits_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_AuxiliaryErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_AuxiliaryErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 if CAN servo is not connected
_pg_user->servoLink = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// 1 if CAN servo is reporting a position error
_pg_user->servoPosition = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Reserved for future use
// Range of reserved_A is 0 to 63.
_pg_user->reserved_A = ((_pg_data[_pg_byteindex]) & 0x3F);
// Reserved for future use
// Range of reserved_B is 0 to 255.
_pg_user->reserved_B = _pg_data[_pg_byteindex + 1];
// Reserved for future use
// Range of reserved_C is 0 to 255.
_pg_user->reserved_C = _pg_data[_pg_byteindex + 2];
// Reserved for future use
// Range of reserved_D is 0 to 255.
_pg_user->reserved_D = _pg_data[_pg_byteindex + 3];
_pg_byteindex += 4; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_AuxiliaryErrorBits_t
/*!
* \brief Encode a ECU_AutronicErrorBits_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_AutronicErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_AutronicErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved
_pg_data[_pg_byteindex] = 0;
// Knock control error
_pg_data[_pg_byteindex + 1] = (uint8_t)_pg_user->knockControl << 7;
// AF closed loop error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->afCloseLoop << 6;
// EEPROM error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->eepromError << 5;
// CMOS RAM error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->cmosRam << 4;
// Over voltage error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->overVoltage << 3;
// Power down error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->powerDown << 2;
// Knock sensor error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->knockSensor << 1;
// Over boost error
_pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->overBoost;
// CAM2 position error
_pg_data[_pg_byteindex + 2] = (uint8_t)_pg_user->cam2Pos << 7;
// CAM1 position error
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->cam1Pos << 6;
// High speed input 1 error
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->highSpeedInput2 << 5;
// High speed input 2 error
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->highSpeedInput1 << 4;
// Set if too many cylinder pulses
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->tooManyCylPulse << 3;
// Set if too few cylinder pulses
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->tooFewCylPulse << 2;
// Set if sync input pulse missing
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->syncInputPulseMissing << 1;
// Set if cylinder input pulse missing
_pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->cylinderInputPulseMissing;
// Air fuel sensor 2 error
_pg_data[_pg_byteindex + 3] = (uint8_t)_pg_user->af2Sensor << 7;
// Air fuel sensor 1 error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->af1Sensor << 6;
// Barometric pressure sensor error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->baroSensor << 5;
// Exhaust back pressure sensor error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->ebpSensor << 4;
// Manifold pressure sensor error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->mapSensor << 3;
// Throttle position sensor error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->tpsSensor << 2;
// Cylinder head temperature sensor error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->chtSensor << 1;
// Manifold pressure sensor error
_pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->matSensor;
_pg_byteindex += 4; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeECU_AutronicErrorBits_t
/*!
* \brief Decode a ECU_AutronicErrorBits_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_AutronicErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_AutronicErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved
// Knock control error
_pg_user->knockControl = (_pg_data[_pg_byteindex + 1] >> 7);
// AF closed loop error
_pg_user->afCloseLoop = ((_pg_data[_pg_byteindex + 1] >> 6) & 0x1);
// EEPROM error
_pg_user->eepromError = ((_pg_data[_pg_byteindex + 1] >> 5) & 0x1);
// CMOS RAM error
_pg_user->cmosRam = ((_pg_data[_pg_byteindex + 1] >> 4) & 0x1);
// Over voltage error
_pg_user->overVoltage = ((_pg_data[_pg_byteindex + 1] >> 3) & 0x1);
// Power down error
_pg_user->powerDown = ((_pg_data[_pg_byteindex + 1] >> 2) & 0x1);
// Knock sensor error
_pg_user->knockSensor = ((_pg_data[_pg_byteindex + 1] >> 1) & 0x1);
// Over boost error
_pg_user->overBoost = ((_pg_data[_pg_byteindex + 1]) & 0x1);
// CAM2 position error
_pg_user->cam2Pos = (_pg_data[_pg_byteindex + 2] >> 7);
// CAM1 position error
_pg_user->cam1Pos = ((_pg_data[_pg_byteindex + 2] >> 6) & 0x1);
// High speed input 1 error
_pg_user->highSpeedInput2 = ((_pg_data[_pg_byteindex + 2] >> 5) & 0x1);
// High speed input 2 error
_pg_user->highSpeedInput1 = ((_pg_data[_pg_byteindex + 2] >> 4) & 0x1);
// Set if too many cylinder pulses
_pg_user->tooManyCylPulse = ((_pg_data[_pg_byteindex + 2] >> 3) & 0x1);
// Set if too few cylinder pulses
_pg_user->tooFewCylPulse = ((_pg_data[_pg_byteindex + 2] >> 2) & 0x1);
// Set if sync input pulse missing
_pg_user->syncInputPulseMissing = ((_pg_data[_pg_byteindex + 2] >> 1) & 0x1);
// Set if cylinder input pulse missing
_pg_user->cylinderInputPulseMissing = ((_pg_data[_pg_byteindex + 2]) & 0x1);
// Air fuel sensor 2 error
_pg_user->af2Sensor = (_pg_data[_pg_byteindex + 3] >> 7);
// Air fuel sensor 1 error
_pg_user->af1Sensor = ((_pg_data[_pg_byteindex + 3] >> 6) & 0x1);
// Barometric pressure sensor error
_pg_user->baroSensor = ((_pg_data[_pg_byteindex + 3] >> 5) & 0x1);
// Exhaust back pressure sensor error
_pg_user->ebpSensor = ((_pg_data[_pg_byteindex + 3] >> 4) & 0x1);
// Manifold pressure sensor error
_pg_user->mapSensor = ((_pg_data[_pg_byteindex + 3] >> 3) & 0x1);
// Throttle position sensor error
_pg_user->tpsSensor = ((_pg_data[_pg_byteindex + 3] >> 2) & 0x1);
// Cylinder head temperature sensor error
_pg_user->chtSensor = ((_pg_data[_pg_byteindex + 3] >> 1) & 0x1);
// Manifold pressure sensor error
_pg_user->matSensor = ((_pg_data[_pg_byteindex + 3]) & 0x1);
_pg_byteindex += 4; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_AutronicErrorBits_t
/*!
* \brief Encode a ECU_ErrorBits_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_ErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Error information for autronic processor
encodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronic);
// Error information for auxiliary processor
encodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliary);
*_pg_bytecount = _pg_byteindex;
}// encodeECU_ErrorBits_t
/*!
* \brief Decode a ECU_ErrorBits_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_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Error information for autronic processor
if(decodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronic) == 0)
return 0;
// Error information for auxiliary processor
if(decodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliary) == 0)
return 0;
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_ErrorBits_t
/*!
* \brief Encode a ECU_ThrottleDelayConfigBits_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_ThrottleDelayConfigBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ThrottleDelayConfigBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// reserved for future use
// Range of reserved is 0 to 127.
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->reserved << 1;
// Set to base the delay on temperature, else the delay is manually set
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->delayOnTemp == true) ? 1 : 0);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeECU_ThrottleDelayConfigBits_t
/*!
* \brief Decode a ECU_ThrottleDelayConfigBits_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_ThrottleDelayConfigBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ThrottleDelayConfigBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// reserved for future use
// Range of reserved is 0 to 127.
_pg_user->reserved = (_pg_data[_pg_byteindex] >> 1);
// Set to base the delay on temperature, else the delay is manually set
_pg_user->delayOnTemp = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_ThrottleDelayConfigBits_t
/*!
* \brief Encode a ECU_ThrottleConfigBits_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_ThrottleConfigBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ThrottleConfigBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Enable pass-through of CAN servo data over serial link
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->servoPassthrough == true) ? 1 : 0) << 7;
// Reserved for future use
// Set if the CAN throttle is detected
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->canThrottleDetected == true) ? 1 : 0) << 1;
// Set if CAN throttle is enabled. This bit is ignored when this packet is sent to the ECU. To enable CAN throttle you must use system commands
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->canThrottle == true) ? 1 : 0);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeECU_ThrottleConfigBits_t
/*!
* \brief Decode a ECU_ThrottleConfigBits_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_ThrottleConfigBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ThrottleConfigBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Enable pass-through of CAN servo data over serial link
_pg_user->servoPassthrough = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// Reserved for future use
// Set if the CAN throttle is detected
_pg_user->canThrottleDetected = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// Set if CAN throttle is enabled. This bit is ignored when this packet is sent to the ECU. To enable CAN throttle you must use system commands
_pg_user->canThrottle = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_ThrottleConfigBits_t
/*!
* \brief Encode a ECU_ThrottleCurveConfigBits_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_ThrottleCurveConfigBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ThrottleCurveConfigBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved for future use
_pg_data[_pg_byteindex] = 0;
// Throttle curve is active
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->curveActive == true) ? 1 : 0);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeECU_ThrottleCurveConfigBits_t
/*!
* \brief Decode a ECU_ThrottleCurveConfigBits_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_ThrottleCurveConfigBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ThrottleCurveConfigBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved for future use
// Throttle curve is active
_pg_user->curveActive = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_ThrottleCurveConfigBits_t
/*!
* \brief Encode a ECU_ECUSettings_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_ECUSettings_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ECUSettings_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Range of powerCycles is 0 to 65535.
uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex);
// Deprecated - DO NOT USE
// Range of customerID_deprecated is 0 to 65535.
uint16ToBeBytes(_pg_user->customerID_deprecated, _pg_data, &_pg_byteindex);
// Range of versionHardware is 0 to 255.
uint8ToBytes(_pg_user->versionHardware, _pg_data, &_pg_byteindex);
// reserved for future use
// Range of reservedA is 0 to 255.
uint8ToBytes(_pg_user->reservedA, _pg_data, &_pg_byteindex);
// reserved for future use
// Range of reservedB is 0 to 255.
uint8ToBytes(_pg_user->reservedB, _pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
}// encodeECU_ECUSettings_t
/*!
* \brief Decode a ECU_ECUSettings_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_ECUSettings_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ECUSettings_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Range of powerCycles is 0 to 65535.
_pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Deprecated - DO NOT USE
// Range of customerID_deprecated is 0 to 65535.
_pg_user->customerID_deprecated = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Range of versionHardware is 0 to 255.
_pg_user->versionHardware = uint8FromBytes(_pg_data, &_pg_byteindex);
// reserved for future use
// Range of reservedA is 0 to 255.
_pg_user->reservedA = uint8FromBytes(_pg_data, &_pg_byteindex);
// reserved for future use
// Range of reservedB is 0 to 255.
_pg_user->reservedB = uint8FromBytes(_pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_ECUSettings_t
/*!
* \brief Encode a ECU_CompileOptions_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_CompileOptions_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_CompileOptions_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// If set, the ECU will pass servo CAN packet data over the serial link
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->servoPassthrough == true) ? 1 : 0) << 7;
// If set, the ECU will decode CAN messages in the PICCOLO_DATA_UP group
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piccoloUplink == true) ? 1 : 0) << 6;
// If set, the ECU supports Autronic message passthrough
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->autronicRelay == true) ? 1 : 0) << 5;
// If set, the ECU supports redundant fuel pump control
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->dualPump == true) ? 1 : 0) << 4;
// If set, the ECU runs a PI controller for fuel pressure. If not set, it uses bang-bang control
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piPump == true) ? 1 : 0) << 3;
// If set, the ECU will automatically compensate for degredation of the MAP sensor over time
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->mapCorrection == true) ? 1 : 0) << 2;
// If set, the ECU watchdog timer is enabled
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->watchdog == true) ? 1 : 0) << 1;
// If set, the ECU is compiled with extra debug functionality enabled
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->debug == true) ? 1 : 0);
_pg_byteindex += 1; // close bit field
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
}// encodeECU_CompileOptions_t
/*!
* \brief Decode a ECU_CompileOptions_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_CompileOptions_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_CompileOptions_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// If set, the ECU will pass servo CAN packet data over the serial link
_pg_user->servoPassthrough = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// If set, the ECU will decode CAN messages in the PICCOLO_DATA_UP group
_pg_user->piccoloUplink = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// If set, the ECU supports Autronic message passthrough
_pg_user->autronicRelay = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// If set, the ECU supports redundant fuel pump control
_pg_user->dualPump = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// If set, the ECU runs a PI controller for fuel pressure. If not set, it uses bang-bang control
_pg_user->piPump = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// If set, the ECU will automatically compensate for degredation of the MAP sensor over time
_pg_user->mapCorrection = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
// If set, the ECU watchdog timer is enabled
_pg_user->watchdog = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// If set, the ECU is compiled with extra debug functionality enabled
_pg_user->debug = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
_pg_byteindex += 1; // close bit field
// Reserved for future use
_pg_byteindex += 1;
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_CompileOptions_t
// end of ECUDefines.c

View File

@ -0,0 +1,218 @@
// ECUDefines.h was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ECUDEFINES_H
#define _ECUDEFINES_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ECUProtocol.h"
typedef struct
{
bool servoLink; //!< 1 if CAN servo is not connected
bool servoPosition; //!< 1 if CAN servo is reporting a position error
unsigned reserved_A : 6; //!< Reserved for future use
unsigned reserved_B : 8; //!< Reserved for future use
unsigned reserved_C : 8; //!< Reserved for future use
unsigned reserved_D : 8; //!< Reserved for future use
}ECU_AuxiliaryErrorBits_t;
//! return the minimum encoded length for the ECU_AuxiliaryErrorBits_t structure
#define getMinLengthOfECU_AuxiliaryErrorBits_t() (4)
//! return the maximum encoded length for the ECU_AuxiliaryErrorBits_t structure
#define getMaxLengthOfECU_AuxiliaryErrorBits_t() (4)
//! Encode a ECU_AuxiliaryErrorBits_t into a byte array
void encodeECU_AuxiliaryErrorBits_t(uint8_t* data, int* bytecount, const ECU_AuxiliaryErrorBits_t* user);
//! Decode a ECU_AuxiliaryErrorBits_t from a byte array
int decodeECU_AuxiliaryErrorBits_t(const uint8_t* data, int* bytecount, ECU_AuxiliaryErrorBits_t* user);
typedef struct
{
unsigned knockControl : 1; //!< Knock control error
unsigned afCloseLoop : 1; //!< AF closed loop error
unsigned eepromError : 1; //!< EEPROM error
unsigned cmosRam : 1; //!< CMOS RAM error
unsigned overVoltage : 1; //!< Over voltage error
unsigned powerDown : 1; //!< Power down error
unsigned knockSensor : 1; //!< Knock sensor error
unsigned overBoost : 1; //!< Over boost error
unsigned cam2Pos : 1; //!< CAM2 position error
unsigned cam1Pos : 1; //!< CAM1 position error
unsigned highSpeedInput2 : 1; //!< High speed input 1 error
unsigned highSpeedInput1 : 1; //!< High speed input 2 error
unsigned tooManyCylPulse : 1; //!< Set if too many cylinder pulses
unsigned tooFewCylPulse : 1; //!< Set if too few cylinder pulses
unsigned syncInputPulseMissing : 1; //!< Set if sync input pulse missing
unsigned cylinderInputPulseMissing : 1; //!< Set if cylinder input pulse missing
unsigned af2Sensor : 1; //!< Air fuel sensor 2 error
unsigned af1Sensor : 1; //!< Air fuel sensor 1 error
unsigned baroSensor : 1; //!< Barometric pressure sensor error
unsigned ebpSensor : 1; //!< Exhaust back pressure sensor error
unsigned mapSensor : 1; //!< Manifold pressure sensor error
unsigned tpsSensor : 1; //!< Throttle position sensor error
unsigned chtSensor : 1; //!< Cylinder head temperature sensor error
unsigned matSensor : 1; //!< Manifold pressure sensor error
}ECU_AutronicErrorBits_t;
//! return the minimum encoded length for the ECU_AutronicErrorBits_t structure
#define getMinLengthOfECU_AutronicErrorBits_t() (4)
//! return the maximum encoded length for the ECU_AutronicErrorBits_t structure
#define getMaxLengthOfECU_AutronicErrorBits_t() (4)
//! Encode a ECU_AutronicErrorBits_t into a byte array
void encodeECU_AutronicErrorBits_t(uint8_t* data, int* bytecount, const ECU_AutronicErrorBits_t* user);
//! Decode a ECU_AutronicErrorBits_t from a byte array
int decodeECU_AutronicErrorBits_t(const uint8_t* data, int* bytecount, ECU_AutronicErrorBits_t* user);
typedef struct
{
ECU_AutronicErrorBits_t autronic; //!< Error information for autronic processor
ECU_AuxiliaryErrorBits_t auxiliary; //!< Error information for auxiliary processor
}ECU_ErrorBits_t;
//! return the minimum encoded length for the ECU_ErrorBits_t structure
#define getMinLengthOfECU_ErrorBits_t() (8)
//! return the maximum encoded length for the ECU_ErrorBits_t structure
#define getMaxLengthOfECU_ErrorBits_t() (8)
//! Encode a ECU_ErrorBits_t into a byte array
void encodeECU_ErrorBits_t(uint8_t* data, int* bytecount, const ECU_ErrorBits_t* user);
//! Decode a ECU_ErrorBits_t from a byte array
int decodeECU_ErrorBits_t(const uint8_t* data, int* bytecount, ECU_ErrorBits_t* user);
typedef struct
{
unsigned reserved : 7; //!< reserved for future use
bool delayOnTemp; //!< Set to base the delay on temperature, else the delay is manually set
}ECU_ThrottleDelayConfigBits_t;
//! return the minimum encoded length for the ECU_ThrottleDelayConfigBits_t structure
#define getMinLengthOfECU_ThrottleDelayConfigBits_t() (1)
//! return the maximum encoded length for the ECU_ThrottleDelayConfigBits_t structure
#define getMaxLengthOfECU_ThrottleDelayConfigBits_t() (1)
//! Encode a ECU_ThrottleDelayConfigBits_t into a byte array
void encodeECU_ThrottleDelayConfigBits_t(uint8_t* data, int* bytecount, const ECU_ThrottleDelayConfigBits_t* user);
//! Decode a ECU_ThrottleDelayConfigBits_t from a byte array
int decodeECU_ThrottleDelayConfigBits_t(const uint8_t* data, int* bytecount, ECU_ThrottleDelayConfigBits_t* user);
typedef struct
{
bool servoPassthrough; //!< Enable pass-through of CAN servo data over serial link
bool canThrottleDetected; //!< Set if the CAN throttle is detected
bool canThrottle; //!< Set if CAN throttle is enabled. This bit is ignored when this packet is sent to the ECU. To enable CAN throttle you must use system commands
}ECU_ThrottleConfigBits_t;
//! return the minimum encoded length for the ECU_ThrottleConfigBits_t structure
#define getMinLengthOfECU_ThrottleConfigBits_t() (1)
//! return the maximum encoded length for the ECU_ThrottleConfigBits_t structure
#define getMaxLengthOfECU_ThrottleConfigBits_t() (1)
//! Encode a ECU_ThrottleConfigBits_t into a byte array
void encodeECU_ThrottleConfigBits_t(uint8_t* data, int* bytecount, const ECU_ThrottleConfigBits_t* user);
//! Decode a ECU_ThrottleConfigBits_t from a byte array
int decodeECU_ThrottleConfigBits_t(const uint8_t* data, int* bytecount, ECU_ThrottleConfigBits_t* user);
typedef struct
{
bool curveActive; //!< Throttle curve is active
}ECU_ThrottleCurveConfigBits_t;
//! return the minimum encoded length for the ECU_ThrottleCurveConfigBits_t structure
#define getMinLengthOfECU_ThrottleCurveConfigBits_t() (1)
//! return the maximum encoded length for the ECU_ThrottleCurveConfigBits_t structure
#define getMaxLengthOfECU_ThrottleCurveConfigBits_t() (1)
//! Encode a ECU_ThrottleCurveConfigBits_t into a byte array
void encodeECU_ThrottleCurveConfigBits_t(uint8_t* data, int* bytecount, const ECU_ThrottleCurveConfigBits_t* user);
//! Decode a ECU_ThrottleCurveConfigBits_t from a byte array
int decodeECU_ThrottleCurveConfigBits_t(const uint8_t* data, int* bytecount, ECU_ThrottleCurveConfigBits_t* user);
typedef struct
{
uint16_t powerCycles;
uint16_t customerID_deprecated; //!< Deprecated - DO NOT USE
uint8_t versionHardware;
uint8_t reservedA; //!< reserved for future use
uint8_t reservedB; //!< reserved for future use
}ECU_ECUSettings_t;
//! return the minimum encoded length for the ECU_ECUSettings_t structure
#define getMinLengthOfECU_ECUSettings_t() (7)
//! return the maximum encoded length for the ECU_ECUSettings_t structure
#define getMaxLengthOfECU_ECUSettings_t() (7)
//! Encode a ECU_ECUSettings_t into a byte array
void encodeECU_ECUSettings_t(uint8_t* data, int* bytecount, const ECU_ECUSettings_t* user);
//! Decode a ECU_ECUSettings_t from a byte array
int decodeECU_ECUSettings_t(const uint8_t* data, int* bytecount, ECU_ECUSettings_t* user);
typedef struct
{
bool servoPassthrough; //!< If set, the ECU will pass servo CAN packet data over the serial link
bool piccoloUplink; //!< If set, the ECU will decode CAN messages in the PICCOLO_DATA_UP group
bool autronicRelay; //!< If set, the ECU supports Autronic message passthrough
bool dualPump; //!< If set, the ECU supports redundant fuel pump control
bool piPump; //!< If set, the ECU runs a PI controller for fuel pressure. If not set, it uses bang-bang control
bool mapCorrection; //!< If set, the ECU will automatically compensate for degredation of the MAP sensor over time
bool watchdog; //!< If set, the ECU watchdog timer is enabled
bool debug; //!< If set, the ECU is compiled with extra debug functionality enabled
}ECU_CompileOptions_t;
//! return the minimum encoded length for the ECU_CompileOptions_t structure
#define getMinLengthOfECU_CompileOptions_t() (2)
//! return the maximum encoded length for the ECU_CompileOptions_t structure
#define getMaxLengthOfECU_CompileOptions_t() (2)
//! Encode a ECU_CompileOptions_t into a byte array
void encodeECU_CompileOptions_t(uint8_t* data, int* bytecount, const ECU_CompileOptions_t* user);
//! Decode a ECU_CompileOptions_t from a byte array
int decodeECU_CompileOptions_t(const uint8_t* data, int* bytecount, ECU_CompileOptions_t* user);
#ifdef __cplusplus
}
#endif
#endif // _ECUDEFINES_H

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,148 @@
// ECUProtocol.c was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "ECUProtocol.h"
/*!
* \brief Lookup label for 'ECUPackets' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ECUPackets_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case PKT_ECU_TELEMETRY_FAST:
return translateECU("PKT_ECU_TELEMETRY_FAST");
case PKT_ECU_TELEMETRY_SLOW_0:
return translateECU("PKT_ECU_TELEMETRY_SLOW_0");
case PKT_ECU_TELEMETRY_SLOW_1:
return translateECU("PKT_ECU_TELEMETRY_SLOW_1");
case PKT_ECU_TELEMETRY_SLOW_2:
return translateECU("PKT_ECU_TELEMETRY_SLOW_2");
case PKT_ECU_TELEMETRY_SLOW_3:
return translateECU("PKT_ECU_TELEMETRY_SLOW_3");
case PKT_ECU_THROTTLE_CALIBRATION:
return translateECU("PKT_ECU_THROTTLE_CALIBRATION");
case PKT_ECU_THROTTLE:
return translateECU("PKT_ECU_THROTTLE");
case PKT_ECU_RPM_COMMAND:
return translateECU("PKT_ECU_RPM_COMMAND");
case PKT_ECU_RPM_CALIBRATION:
return translateECU("PKT_ECU_RPM_CALIBRATION");
case PKT_ECU_HARDWARE_CONFIG:
return translateECU("PKT_ECU_HARDWARE_CONFIG");
case PKT_ECU_SOFTWARE_VERSION:
return translateECU("PKT_ECU_SOFTWARE_VERSION");
case PKT_ECU_TPS_DELAY_CONFIG:
return translateECU("PKT_ECU_TPS_DELAY_CONFIG");
case PKT_ECU_TELEMETRY_SETTINGS:
return translateECU("PKT_ECU_TELEMETRY_SETTINGS");
case PKT_ECU_PUMP_CONFIG:
return translateECU("PKT_ECU_PUMP_CONFIG");
case PKT_ECU_ERROR_MSG:
return translateECU("PKT_ECU_ERROR_MSG");
case PKT_ECU_POWER_CYCLES:
return translateECU("PKT_ECU_POWER_CYCLES");
case PKT_ECU_PUMP_2_CONFIG:
return translateECU("PKT_ECU_PUMP_2_CONFIG");
case PKT_ECU_PUMP_DEBUG:
return translateECU("PKT_ECU_PUMP_DEBUG");
case PKT_ECU_TOTAL_ENGINE_TIME:
return translateECU("PKT_ECU_TOTAL_ENGINE_TIME");
case PKT_ECU_SYS_CMD:
return translateECU("PKT_ECU_SYS_CMD");
case PKT_ECU_USER_DATA:
return translateECU("PKT_ECU_USER_DATA");
case PKT_ECU_THROTTLE_CURVE_0:
return translateECU("PKT_ECU_THROTTLE_CURVE_0");
case PKT_ECU_THROTTLE_CURVE_1:
return translateECU("PKT_ECU_THROTTLE_CURVE_1");
case PKT_ECU_GPIO:
return translateECU("PKT_ECU_GPIO");
case PKT_ECU_SETTINGS_DATA:
return translateECU("PKT_ECU_SETTINGS_DATA");
case PKT_ECU_CHT_LOOP:
return translateECU("PKT_ECU_CHT_LOOP");
}
}
/*!
* \brief Lookup label for 'ECUSystemCommands' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ECUSystemCommands_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case CMD_ECU_CALIBRATE_ANALOG_CLOSED:
return translateECU("CMD_ECU_CALIBRATE_ANALOG_CLOSED");
case CMD_ECU_CALIBRATE_ANALOG_OPEN:
return translateECU("CMD_ECU_CALIBRATE_ANALOG_OPEN");
case CMD_ECU_CALIBRATE_PULSE_CLOSED:
return translateECU("CMD_ECU_CALIBRATE_PULSE_CLOSED");
case CMD_ECU_CALIBRATE_PULSE_OPEN:
return translateECU("CMD_ECU_CALIBRATE_PULSE_OPEN");
case CMD_ECU_CALIBRATE_PULSE_WRITE:
return translateECU("CMD_ECU_CALIBRATE_PULSE_WRITE");
case CMD_ECU_SET_OUTPUT_DRIVER:
return translateECU("CMD_ECU_SET_OUTPUT_DRIVER");
case CMD_ECU_SET_THROTTLE_CURVE_ACTIVE:
return translateECU("CMD_ECU_SET_THROTTLE_CURVE_ACTIVE");
case CMD_ECU_SET_THROTTLE_CURVE_ELEMENT:
return translateECU("CMD_ECU_SET_THROTTLE_CURVE_ELEMENT");
case CMD_ECU_REQUEST_THROTTLE_CURVE_DATA:
return translateECU("CMD_ECU_REQUEST_THROTTLE_CURVE_DATA");
case CMD_ECU_RESET_FUEL_USED:
return translateECU("CMD_ECU_RESET_FUEL_USED");
case CMD_ECU_SET_FUEL_USED_DIVISOR:
return translateECU("CMD_ECU_SET_FUEL_USED_DIVISOR");
case CMD_ECU_FUEL_USED_RESET_ON_STARTUP:
return translateECU("CMD_ECU_FUEL_USED_RESET_ON_STARTUP");
case CMD_ECU_SET_GOVERNOR_MODE:
return translateECU("CMD_ECU_SET_GOVERNOR_MODE");
case CMD_ECU_SET_SERVO_CAN_MODE:
return translateECU("CMD_ECU_SET_SERVO_CAN_MODE");
case CMD_ECU_RESET_INTO_BOOTLOADER:
return translateECU("CMD_ECU_RESET_INTO_BOOTLOADER");
case CMD_ECU_RESET_DEFAULT_SETTINGS:
return translateECU("CMD_ECU_RESET_DEFAULT_SETTINGS");
case CMD_ECU_SET_SERIAL_MODE:
return translateECU("CMD_ECU_SET_SERIAL_MODE");
case CMD_ECU_SET_NODE_ID:
return translateECU("CMD_ECU_SET_NODE_ID");
case CMD_ECU_SET_USER_DATA:
return translateECU("CMD_ECU_SET_USER_DATA");
case CMD_ECU_RESET_ENGINE_TIME:
return translateECU("CMD_ECU_RESET_ENGINE_TIME");
case CMD_ECU_RESET_ECU:
return translateECU("CMD_ECU_RESET_ECU");
}
}
// end of ECUProtocol.c

View File

@ -0,0 +1,211 @@
// ECUProtocol.h was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ECUPROTOCOL_H
#define _ECUPROTOCOL_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
* \mainpage ECU protocol stack
*
* ECU ICD
*
* The protocol API enumeration is incremented anytime the protocol is changed
* in a way that affects compatibility with earlier versions of the protocol.
* The protocol enumeration for this version is: 11
*
* The protocol version is 7.0
*/
#include <stdbool.h>
#include <stdint.h>
//! \return the protocol API enumeration
#define getECUApi() 11
//! \return the protocol version string
#define getECUVersion() "7.0"
// Translation provided externally. The macro takes a `const char *` and returns a `const char *`
#ifndef translateECU
#define translateECU(x) x
#endif
/*!
* Enumeration defining RESET commands for ECU settings
*/
typedef enum
{
ECU_RESET_THROTTLE = 0x01,//!< Reset throttle settings to default values
ECU_RESET_PUMP = 0x02, //!< Reset pump settings to default values
ECU_RESET_GOVERNOR = 0x04,//!< Reset governor settings to default values
ECU_RESET_TELEMETRY = 0x08,//!< Reset telemetry settings to default values
ECU_RESET_ALL = 0xFF //!< Reset all ECU settings to default values
} ECUResetCommands;
typedef enum
{
ECU_DEBUG_RESET_STACK_OVERFLOW = 0x01,
ECU_DEBUG_RESET_STACK_UNDERFLOW,
ECU_DEBUG_RESET_DIVIDE_BY_ZERO,
ECU_DEBUG_RESET_INFINITE_LOOP
} ECUDebugResetTests;
/*!
* ECU throttle position signal source enumeration
*/
typedef enum
{
ECU_TPS_SRC_NONE = 0x00, //!< No throttle source
ECU_TPS_SRC_RPM = 0x01, //!< Throttle is commanded by RPM governor
ECU_TPS_SRC_PWM = 0x02, //!< Throttle is commanded from PWM input
ECU_TPS_SRC_SERIAL = 0x04,//!< Throttle is commanded from serial command packet
ECU_TPS_SRC_CAN = 0x08, //!< Throttle is commanded from CAN command packet
ECU_TPS_SRC_ANALOG = 0x0F //!< Throttle is commanded from analog input
} ECUThrottleSource;
typedef enum
{
ECU_DUAL_PUMP_MODE_DISABLED = 0x00,//!< Both pumps disabled
ECU_DUAL_PUMP_MODE_PRIMARY_CE, //!< Primary pump running
ECU_DUAL_PUMP_MODE_SECONDARY_TSA,//!< Secondary pump running
ECU_DUAL_PUMP_MODE_BOTH //!< Both pumps running
} DualFuelPumpMode;
typedef enum
{
ECU_DUAL_PUMP_STATE_RESET = 0x00,//!< Pump state machine is in the initial reset state
ECU_DUAL_PUMP_STATE_CMD, //!< Pump was explicitly commanded to the current state
ECU_DUAL_PUMP_STATE_TEST, //!< Pump is running in manual test mode
ECU_DUAL_PUMP_STATE_FAILURE //!< Pump has switched over due to detected failure
} DualFuelPumpState;
typedef enum
{
ECU_DUAL_PUMP_CMD_SET_PUMP = 0x01,//!< Switch to a particular pump mode
ECU_DUAL_PUMP_CMD_TEST_PUMP = 0x02 //!< Temporarily switch to a particular pump mode
} DualFuelPumpCommands;
/*!
* ECU packet identifier (ID) definitions
*/
typedef enum
{
PKT_ECU_TELEMETRY_FAST = 0x00, //!< High priority telemetry data from the ECU
PKT_ECU_TELEMETRY_SLOW_0, //!< First low priority telemetry packet from the ECU
PKT_ECU_TELEMETRY_SLOW_1, //!< Second low priority telemetry packet from the ECU
PKT_ECU_TELEMETRY_SLOW_2, //!< Third low priority telemetry packet from the ECU
PKT_ECU_TELEMETRY_SLOW_3, //!< Fourth low priority telemetry packet from the ECU (reserved for future use)
PKT_ECU_THROTTLE_CALIBRATION = 0x05, //!< Throttle calibration values
PKT_ECU_THROTTLE, //!< ECU throttle command
PKT_ECU_THROTTLE_COMBINED, //!< ECU Throttle command (position and pulse)
PKT_ECU_RPM_COMMAND, //!< RPM setpoint command
PKT_ECU_RPM_CALIBRATION, //!< RPM control loop calibration values
PKT_ECU_HARDWARE_CONFIG, //!< Serial number information
PKT_ECU_SOFTWARE_VERSION, //!< Firmware version information
PKT_ECU_TPS_DELAY_CONFIG, //!< Throttle delay configuration
PKT_ECU_TELEMETRY_SETTINGS, //!< Telemetry configuration
PKT_ECU_PUMP_CONFIG, //!< ECU Pump configuration packet 1 of 2
PKT_ECU_ERROR_MSG, //!< Error messages
PKT_ECU_POWER_CYCLES = 0x10, //!< System information
PKT_ECU_PUMP_2_CONFIG, //!< ECU Pump configuration packet 2 of 2
PKT_ECU_PUMP_DEBUG, //!< Pump debug information
PKT_ECU_TOTAL_ENGINE_TIME, //!< Total engine run-time
PKT_ECU_SYS_CMD, //!< ECU System command
PKT_ECU_USER_DATA, //!< User-configurable data bytes
PKT_ECU_THROTTLE_CURVE_0, //!< Throttle curve data, packet 1 of 2
PKT_ECU_THROTTLE_CURVE_1, //!< Throttle curve data, packet 2 of 2
PKT_ECU_GPIO, //!< GPIO settings
PKT_ECU_SETTINGS_DATA, //!< Non-volatile settings information
PKT_ECU_AUTRONIC_MEMORY, //!< Read or write Autronic RAM
PKT_ECU_CHT_LOOP, //!< Control loop settings for the CHT control loop
PKT_ECU_CANAUTRONIC_RELAY = 0x1F //!< Relay Autronic data across CAN
} ECUPackets;
//! \return the label of a 'ECUPackets' enum entry, based on its value
const char* ECUPackets_EnumLabel(int value);
typedef enum
{
ECU_CE_CAL_TITLE_1 = 0xA0,
ECU_CE_CAL_TITLE_2,
ECU_CE_CAL_TITLE_3
} ECUSpecialPackets;
/*!
* These system command identifiers are used with the [system
* command](#PKT_ECU_SYS_CMD) packet.
*/
typedef enum
{
CMD_ECU_CALIBRATE_ANALOG_CLOSED = 0x01,//!< 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.
CMD_ECU_CALIBRATE_ANALOG_OPEN, //!< 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.
CMD_ECU_CALIBRATE_PULSE_CLOSED, //!< 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.
CMD_ECU_CALIBRATE_PULSE_OPEN, //!< 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.
CMD_ECU_CALIBRATE_PULSE_WRITE, //!< 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.
CMD_ECU_SET_OUTPUT_DRIVER = 0x0A, //!< Set one of four high-current output drivers. Send two bytes after the command byte. Byte 1: Driver - Select driver number (1, 2, 3 or 4) Byte 2: Status - Set driver status (1 = ON, 0 = OFF)
CMD_ECU_SET_THROTTLE_CURVE_ACTIVE, //!< Turn the throttle linearization curve either on or off. Byte 1: 1 = ON 0 = OFF
CMD_ECU_SET_THROTTLE_CURVE_ELEMENT, //!< Set individual elements in the throttle linearization lookup table. Byte 1 = Element number (0 to 10, inclusive) Byte 2 = Value (0 to 200 inclusive) Each bit of the 'value' byte represents 0.5% throttle. So, 0 = 0% and 200 = 100%
CMD_ECU_REQUEST_THROTTLE_CURVE_DATA, //!< 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.
CMD_ECU_RESET_FUEL_USED = 0x10, //!< Reset the FuelUsed value. This will set the FuelUsed data to zero.
CMD_ECU_SET_FUEL_USED_DIVISOR, //!< Configure the FuelUsed divisor. This is an unsigned 16-bit value. 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).
CMD_ECU_FUEL_USED_RESET_ON_STARTUP, //!< 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. 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up
CMD_ECU_SET_GOVERNOR_MODE = 0x20, //!< Manually set the RPM governor mode Byte1 = MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command
CMD_ECU_SET_SERVO_CAN_MODE = 0x28,
CMD_ECU_RESET_INTO_BOOTLOADER = 0x30,//!< Reset the ECU into bootloader mode
CMD_ECU_RESET_DEFAULT_SETTINGS, //!< Set ECU settings to their default values
CMD_ECU_SET_SERIAL_MODE = 0x40, //!< Set the serial relay mode used for Autronic relay
CMD_ECU_SET_NODE_ID = 0x50, //!< Set the address (CAN node ID) for the ECU
CMD_ECU_SET_USER_DATA = 0x60, //!< Save a single byte of USER_DATA in EEPROM Byte1 = USER_DATA address (0 to 7) Byte2 = USER_DATA variable (0x00 to 0xFF)
CMD_ECU_RESET_ENGINE_TIME = 0xA5, //!< Reset the engine time counter. If no further bytes are sent after the RESET_ENGINE_TIME command, this will set the engine time (in seconds) to zero. Note that the 'Total Engine Time' counter is not reset. To set the engine time to a specific value, send the engine time in seconds as a 3-byte (big endian) number after the RESET_ENGINE_TIME command.
CMD_ECU_RESET_ECU = 0xD0 //!< Cause a system reset
} ECUSystemCommands;
//! \return the label of a 'ECUSystemCommands' enum entry, based on its value
const char* ECUSystemCommands_EnumLabel(int value);
// The prototypes below provide an interface to the packets.
// They are not auto-generated functions, but must be hand-written
//! \return the packet data pointer from the packet
uint8_t* getECUPacketData(void* pkt);
//! \return the packet data pointer from the packet, const
const uint8_t* getECUPacketDataConst(const void* pkt);
//! Complete a packet after the data have been encoded
void finishECUPacket(void* pkt, int size, uint32_t packetID);
//! \return the size of a packet from the packet header
int getECUPacketSize(const void* pkt);
//! \return the ID of a packet from the packet header
uint32_t getECUPacketID(const void* pkt);
#ifdef __cplusplus
}
#endif
#endif // _ECUPROTOCOL_H

View File

@ -0,0 +1,642 @@
// ECUSettings.c was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "ECUSettings.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Encode a ECU_PumpOptionBits_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_PumpOptionBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_PumpOptionBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved for future use
// Range of reserved is 0 to 255.
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->reserved;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeECU_PumpOptionBits_t
/*!
* \brief Decode a ECU_PumpOptionBits_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_PumpOptionBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_PumpOptionBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved for future use
// Range of reserved is 0 to 255.
_pg_user->reserved = _pg_data[_pg_byteindex];
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeECU_PumpOptionBits_t
/*!
* \brief Create the ECU_ThrottleSettings packet
*
* Throttle 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_ThrottleSettingsPacketStructure(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;
unsigned _pg_i = 0;
// Throttle open PWM value
// Range of pulseOpen is 0 to 65535.
uint16ToBeBytes(_pg_user->pulseOpen, _pg_data, &_pg_byteindex);
// Throttle closed PWM value
// Range of pulseClosed is 0 to 65535.
uint16ToBeBytes(_pg_user->pulseClosed, _pg_data, &_pg_byteindex);
// Throttle input open PWM value
// Range of pulseInputOpen is 0 to 4095.
_pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputOpen, 4095);
_pg_data[_pg_byteindex + 1] = (uint8_t)(_pg_tempbitfield << 4);
_pg_tempbitfield >>= 4;
_pg_data[_pg_byteindex] = (uint8_t)_pg_tempbitfield;
// Throttle input closed PWM value
// Range of pulseInputClosed is 0 to 4095.
_pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputClosed, 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
// Throttle delay, constant value
// Range of delay is 0 to 255.
uint8ToBytes(_pg_user->delay, _pg_data, &_pg_byteindex);
// Throttle delay, minimum value
// Range of minDelay is 0 to 255.
uint8ToBytes(_pg_user->minDelay, _pg_data, &_pg_byteindex);
// Throttle delay, minimum value
// Range of maxDelay is 0 to 255.
uint8ToBytes(_pg_user->maxDelay, _pg_data, &_pg_byteindex);
encodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig);
// Throttle dashpot soft limit value
// Range of softLimit is 0 to 255.
uint8ToBytes(_pg_user->softLimit, _pg_data, &_pg_byteindex);
// Throttle dashpot hard limit value
// Range of hardLimit is 0 to 255.
uint8ToBytes(_pg_user->hardLimit, _pg_data, &_pg_byteindex);
// Throttle dashpot falloff rate
// Range of falloffRate is 0 to 255.
uint8ToBytes(_pg_user->falloffRate, _pg_data, &_pg_byteindex);
// Throttle curve lookup table elements
// Range of curve is 0 to 255.
for(_pg_i = 0; _pg_i < 11; _pg_i++)
uint8ToBytes(_pg_user->curve[_pg_i], _pg_data, &_pg_byteindex);
// Throttle curve config bits
encodeECU_ThrottleCurveConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->curveConfig);
encodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config);
// Range of analogSpan1 is 0 to 255.
uint8ToBytes(_pg_user->analogSpan1, _pg_data, &_pg_byteindex);
// Range of analogSpan2 is 0 to 65535.
uint16ToBeBytes(_pg_user->analogSpan2, _pg_data, &_pg_byteindex);
// Range of throttleTarget is 0 to 255.
uint8ToBytes(_pg_user->throttleTarget, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleSettingsPacketID());
}// encodeECU_ThrottleSettingsPacketStructure
/*!
* \brief Decode the ECU_ThrottleSettings packet
*
* Throttle 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_ThrottleSettingsPacketStructure(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;
unsigned _pg_i = 0;
// Verify the packet identifier
if(getECUPacketID(_pg_pkt) != getECU_ThrottleSettingsPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getECUPacketSize(_pg_pkt);
if(_pg_numbytes < getECU_ThrottleSettingsMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getECUPacketDataConst(_pg_pkt);
// Throttle open PWM value
// Range of pulseOpen is 0 to 65535.
_pg_user->pulseOpen = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Throttle closed PWM value
// Range of pulseClosed is 0 to 65535.
_pg_user->pulseClosed = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Throttle input open PWM value
// Range of pulseInputOpen is 0 to 4095.
_pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xFF);
_pg_tempbitfield <<= 4;
_pg_tempbitfield |= (_pg_data[_pg_byteindex + 1] >> 4);
_pg_user->pulseInputOpen = _pg_tempbitfield;
// Throttle input closed PWM value
// Range of pulseInputClosed is 0 to 4095.
_pg_tempbitfield = (_pg_data[_pg_byteindex + 1] & 0xF);
_pg_tempbitfield <<= 8;
_pg_tempbitfield |= _pg_data[_pg_byteindex + 2];
_pg_user->pulseInputClosed = _pg_tempbitfield;
_pg_byteindex += 3; // close bit field
// Throttle delay, constant value
// Range of delay is 0 to 255.
_pg_user->delay = uint8FromBytes(_pg_data, &_pg_byteindex);
// Throttle delay, minimum value
// Range of minDelay is 0 to 255.
_pg_user->minDelay = uint8FromBytes(_pg_data, &_pg_byteindex);
// Throttle delay, minimum value
// Range of maxDelay is 0 to 255.
_pg_user->maxDelay = uint8FromBytes(_pg_data, &_pg_byteindex);
if(decodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig) == 0)
return 0;
// Throttle dashpot soft limit value
// Range of softLimit is 0 to 255.
_pg_user->softLimit = uint8FromBytes(_pg_data, &_pg_byteindex);
// Throttle dashpot hard limit value
// Range of hardLimit is 0 to 255.
_pg_user->hardLimit = uint8FromBytes(_pg_data, &_pg_byteindex);
// Throttle dashpot falloff rate
// Range of falloffRate is 0 to 255.
_pg_user->falloffRate = uint8FromBytes(_pg_data, &_pg_byteindex);
// Throttle curve lookup table elements
// Range of curve is 0 to 255.
for(_pg_i = 0; _pg_i < 11; _pg_i++)
_pg_user->curve[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex);
// Throttle curve config bits
if(decodeECU_ThrottleCurveConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->curveConfig) == 0)
return 0;
if(decodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config) == 0)
return 0;
// Range of analogSpan1 is 0 to 255.
_pg_user->analogSpan1 = uint8FromBytes(_pg_data, &_pg_byteindex);
// Range of analogSpan2 is 0 to 65535.
_pg_user->analogSpan2 = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Range of throttleTarget is 0 to 255.
_pg_user->throttleTarget = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeECU_ThrottleSettingsPacketStructure
/*!
* \brief Create the ECU_FuelUsedSettings packet
*
* Throttle 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_FuelUsedSettingsPacketStructure(void* _pg_pkt, const ECU_FuelUsedSettings_t* _pg_user)
{
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Range of resetOnStartup is 0 to 255.
uint8ToBytes(_pg_user->resetOnStartup, _pg_data, &_pg_byteindex);
// Range of divisor is 0 to 65535.
uint16ToBeBytes(_pg_user->divisor, _pg_data, &_pg_byteindex);
// Range of offset is 0 to 65535.
uint16ToBeBytes(_pg_user->offset, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_FuelUsedSettingsPacketID());
}// encodeECU_FuelUsedSettingsPacketStructure
/*!
* \brief Decode the ECU_FuelUsedSettings packet
*
* Throttle 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_FuelUsedSettingsPacketStructure(const void* _pg_pkt, ECU_FuelUsedSettings_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getECUPacketID(_pg_pkt) != getECU_FuelUsedSettingsPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getECUPacketSize(_pg_pkt);
if(_pg_numbytes < getECU_FuelUsedSettingsMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getECUPacketDataConst(_pg_pkt);
// Range of resetOnStartup is 0 to 255.
_pg_user->resetOnStartup = uint8FromBytes(_pg_data, &_pg_byteindex);
// Range of divisor is 0 to 65535.
_pg_user->divisor = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Range of offset is 0 to 65535.
_pg_user->offset = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeECU_FuelUsedSettingsPacketStructure
/*!
* \brief Create the ECU_GovernorSettings packet
*
* Throttle 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_GovernorSettingsPacketStructure(void* _pg_pkt, const ECU_GovernorSettings_t* _pg_user)
{
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Range of pGain is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->pGain, _pg_data, &_pg_byteindex);
// Range of iGain is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->iGain, _pg_data, &_pg_byteindex);
// Range of dGain is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->dGain, _pg_data, &_pg_byteindex);
// Range of scalePower is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->scalePower, _pg_data, &_pg_byteindex);
// Range of maxRPM is 0.0f to 25500.0f.
float32ScaledTo1UnsignedBytes(_pg_user->maxRPM, _pg_data, &_pg_byteindex, 0.0f, 0.01f);
// Range of minRPM is 0.0f to 25500.0f.
float32ScaledTo1UnsignedBytes(_pg_user->minRPM, _pg_data, &_pg_byteindex, 0.0f, 0.01f);
// Range of mode is 0 to 255.
uint8ToBytes(_pg_user->mode, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_GovernorSettingsPacketID());
}// encodeECU_GovernorSettingsPacketStructure
/*!
* \brief Decode the ECU_GovernorSettings packet
*
* Throttle 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_GovernorSettingsPacketStructure(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_GovernorSettingsPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getECUPacketSize(_pg_pkt);
if(_pg_numbytes < getECU_GovernorSettingsMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getECUPacketDataConst(_pg_pkt);
// Range of pGain is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->pGain = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of iGain is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->iGain = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of dGain is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->dGain = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of scalePower is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->scalePower = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of maxRPM is 0.0f to 25500.0f.
_pg_user->maxRPM = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/0.01f);
// Range of minRPM is 0.0f to 25500.0f.
_pg_user->minRPM = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/0.01f);
// Range of mode is 0 to 255.
_pg_user->mode = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeECU_GovernorSettingsPacketStructure
/*!
* \brief Create the ECU_PumpSettings packet
*
* Throttle 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_PumpSettingsPacketStructure(void* _pg_pkt, const ECU_PumpSettings_t* _pg_user)
{
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Pump proportional gain
// Range of kp is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->kp, _pg_data, &_pg_byteindex);
// Pump integral gain
// Range of ki is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->ki, _pg_data, &_pg_byteindex);
// Pump IMC (internal model) gain
// Range of km is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->km, _pg_data, &_pg_byteindex);
// Pump lower pressure limit (PSI)
// Range of pressureLowerLimit is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->pressureLowerLimit, _pg_data, &_pg_byteindex);
// Pump upper pressure limit (PSI)
// Range of pressureUpperLimit is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->pressureUpperLimit, _pg_data, &_pg_byteindex);
// Fuel pressure setpoint
// Range of pressureSetpoint is -3.402823466e+38f to 3.402823466e+38f.
float32ToBeBytes((float)_pg_user->pressureSetpoint, _pg_data, &_pg_byteindex);
// Range of minimumPWM is 0 to 255.
uint8ToBytes(_pg_user->minimumPWM, _pg_data, &_pg_byteindex);
// Range of maximumPWM is 0 to 255.
uint8ToBytes(_pg_user->maximumPWM, _pg_data, &_pg_byteindex);
// Pump duty cycle ramp rate
// Range of rampRate is 0 to 255.
uint8ToBytes(_pg_user->rampRate, _pg_data, &_pg_byteindex);
// Pump control system options
encodeECU_PumpOptionBits_t(_pg_data, &_pg_byteindex, &_pg_user->options);
// Reserved for future use
// Range of reservedA is 0 to 255.
uint8ToBytes(_pg_user->reservedA, _pg_data, &_pg_byteindex);
// Reserved for future use
// Range of reservedB is 0 to 255.
uint8ToBytes(_pg_user->reservedB, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PumpSettingsPacketID());
}// encodeECU_PumpSettingsPacketStructure
/*!
* \brief Decode the ECU_PumpSettings packet
*
* Throttle 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_PumpSettingsPacketStructure(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_PumpSettingsPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getECUPacketSize(_pg_pkt);
if(_pg_numbytes < getECU_PumpSettingsMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getECUPacketDataConst(_pg_pkt);
// Pump proportional gain
// Range of kp is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->kp = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Pump integral gain
// Range of ki is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->ki = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Pump IMC (internal model) gain
// Range of km is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->km = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Pump lower pressure limit (PSI)
// Range of pressureLowerLimit is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->pressureLowerLimit = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Pump upper pressure limit (PSI)
// Range of pressureUpperLimit is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->pressureUpperLimit = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Fuel pressure setpoint
// Range of pressureSetpoint is -3.402823466e+38f to 3.402823466e+38f.
_pg_user->pressureSetpoint = float32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of minimumPWM is 0 to 255.
_pg_user->minimumPWM = uint8FromBytes(_pg_data, &_pg_byteindex);
// Range of maximumPWM is 0 to 255.
_pg_user->maximumPWM = uint8FromBytes(_pg_data, &_pg_byteindex);
// Pump duty cycle ramp rate
// Range of rampRate is 0 to 255.
_pg_user->rampRate = uint8FromBytes(_pg_data, &_pg_byteindex);
// Pump control system options
if(decodeECU_PumpOptionBits_t(_pg_data, &_pg_byteindex, &_pg_user->options) == 0)
return 0;
// Reserved for future use
// Range of reservedA is 0 to 255.
_pg_user->reservedA = uint8FromBytes(_pg_data, &_pg_byteindex);
// Reserved for future use
// Range of reservedB is 0 to 255.
_pg_user->reservedB = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeECU_PumpSettingsPacketStructure
/*!
* \brief Create the ECU_ECUData packet
*
* User 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_ECUDataPacketStructure(void* _pg_pkt, const ECU_ECUData_t* _pg_user)
{
uint8_t* _pg_data = getECUPacketData(_pg_pkt);
int _pg_byteindex = 0;
unsigned _pg_i = 0;
// Range of powerCycles is 0 to 65535.
uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex);
// Range of engineTime is 0 to 4294967295.
uint32ToBeBytes(_pg_user->engineTime, _pg_data, &_pg_byteindex);
// Range of engineTimeTotal is 0 to 4294967295.
uint32ToBeBytes(_pg_user->engineTimeTotal, _pg_data, &_pg_byteindex);
// Range of fuelUsedOverflows is 0 to 65535.
uint16ToBeBytes(_pg_user->fuelUsedOverflows, _pg_data, &_pg_byteindex);
// Range of userValues is 0 to 255.
for(_pg_i = 0; _pg_i < 8; _pg_i++)
uint8ToBytes(_pg_user->userValues[_pg_i], _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ECUDataPacketID());
}// encodeECU_ECUDataPacketStructure
/*!
* \brief Decode the ECU_ECUData packet
*
* User 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_ECUDataPacketStructure(const void* _pg_pkt, ECU_ECUData_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_ECUDataPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getECUPacketSize(_pg_pkt);
if(_pg_numbytes < getECU_ECUDataMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getECUPacketDataConst(_pg_pkt);
// Range of powerCycles is 0 to 65535.
_pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Range of engineTime is 0 to 4294967295.
_pg_user->engineTime = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of engineTimeTotal is 0 to 4294967295.
_pg_user->engineTimeTotal = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// Range of fuelUsedOverflows is 0 to 65535.
_pg_user->fuelUsedOverflows = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Range of userValues is 0 to 255.
for(_pg_i = 0; _pg_i < 8; _pg_i++)
_pg_user->userValues[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeECU_ECUDataPacketStructure
// end of ECUSettings.c

View File

@ -0,0 +1,224 @@
// ECUSettings.h was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ECUSETTINGS_H
#define _ECUSETTINGS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ECUProtocol.h"
#include "ECUDefines.h"
/*!
* ECU settings packets (not available on CAN or RS232 interfaces)
*/
typedef enum
{
PKT_ECU_SETTINGS_THROTTLE = 0xF0, //!< Throttle settings
PKT_ECU_SETTINGS_PUMP = 0xF1, //!< Throttle settings
PKT_ECU_SETTINGS_GOVERNOR = 0xF2, //!< Throttle settings
PKT_ECU_SETTINGS_TELEMETRY = 0xF3, //!< Throttle settings
PKT_ECU_SETTINGS_FUEL_USED = 0xF4, //!< Throttle settings
PKT_ECU_SETTINGS_ENGINE_TIME = 0xF5, //!< Engine run time
PKT_ECU_SETTINGS_USER = 0xFA //!< User data
} ECUSettingsPackets;
typedef struct
{
unsigned reserved : 8; //!< Reserved for future use
}ECU_PumpOptionBits_t;
//! return the minimum encoded length for the ECU_PumpOptionBits_t structure
#define getMinLengthOfECU_PumpOptionBits_t() (1)
//! return the maximum encoded length for the ECU_PumpOptionBits_t structure
#define getMaxLengthOfECU_PumpOptionBits_t() (1)
//! Encode a ECU_PumpOptionBits_t into a byte array
void encodeECU_PumpOptionBits_t(uint8_t* data, int* bytecount, const ECU_PumpOptionBits_t* user);
//! Decode a ECU_PumpOptionBits_t from a byte array
int decodeECU_PumpOptionBits_t(const uint8_t* data, int* bytecount, ECU_PumpOptionBits_t* user);
/*!
* Throttle settings
*/
typedef struct
{
uint16_t pulseOpen; //!< Throttle open PWM value
uint16_t pulseClosed; //!< Throttle closed PWM value
uint16_t pulseInputOpen; //!< Throttle input open PWM value
uint16_t pulseInputClosed; //!< Throttle input closed PWM value
uint8_t delay; //!< Throttle delay, constant value
uint8_t minDelay; //!< Throttle delay, minimum value
uint8_t maxDelay; //!< Throttle delay, minimum value
ECU_ThrottleDelayConfigBits_t delayConfig;
uint8_t softLimit; //!< Throttle dashpot soft limit value
uint8_t hardLimit; //!< Throttle dashpot hard limit value
uint8_t falloffRate; //!< Throttle dashpot falloff rate
uint8_t curve[11]; //!< Throttle curve lookup table elements
ECU_ThrottleCurveConfigBits_t curveConfig; //!< Throttle curve config bits
ECU_ThrottleConfigBits_t config;
uint8_t analogSpan1;
uint16_t analogSpan2;
uint8_t throttleTarget;
}ECU_ThrottleSettings_t;
//! Create the ECU_ThrottleSettings packet
void encodeECU_ThrottleSettingsPacketStructure(void* pkt, const ECU_ThrottleSettings_t* user);
//! Decode the ECU_ThrottleSettings packet
int decodeECU_ThrottleSettingsPacketStructure(const void* pkt, ECU_ThrottleSettings_t* user);
//! return the packet ID for the ECU_ThrottleSettings packet
#define getECU_ThrottleSettingsPacketID() (PKT_ECU_SETTINGS_THROTTLE)
//! return the minimum encoded length for the ECU_ThrottleSettings packet
#define getECU_ThrottleSettingsMinDataLength() (31)
//! return the maximum encoded length for the ECU_ThrottleSettings packet
#define getECU_ThrottleSettingsMaxDataLength() (31)
/*!
* Throttle settings
*/
typedef struct
{
uint8_t resetOnStartup;
uint16_t divisor;
uint16_t offset;
}ECU_FuelUsedSettings_t;
//! Create the ECU_FuelUsedSettings packet
void encodeECU_FuelUsedSettingsPacketStructure(void* pkt, const ECU_FuelUsedSettings_t* user);
//! Decode the ECU_FuelUsedSettings packet
int decodeECU_FuelUsedSettingsPacketStructure(const void* pkt, ECU_FuelUsedSettings_t* user);
//! return the packet ID for the ECU_FuelUsedSettings packet
#define getECU_FuelUsedSettingsPacketID() (PKT_ECU_SETTINGS_FUEL_USED)
//! return the minimum encoded length for the ECU_FuelUsedSettings packet
#define getECU_FuelUsedSettingsMinDataLength() (5)
//! return the maximum encoded length for the ECU_FuelUsedSettings packet
#define getECU_FuelUsedSettingsMaxDataLength() (5)
/*!
* Throttle settings
*/
typedef struct
{
float pGain;
float iGain;
float dGain;
float scalePower;
float maxRPM;
float minRPM;
uint8_t mode;
}ECU_GovernorSettings_t;
//! Create the ECU_GovernorSettings packet
void encodeECU_GovernorSettingsPacketStructure(void* pkt, const ECU_GovernorSettings_t* user);
//! Decode the ECU_GovernorSettings packet
int decodeECU_GovernorSettingsPacketStructure(const void* pkt, ECU_GovernorSettings_t* user);
//! return the packet ID for the ECU_GovernorSettings packet
#define getECU_GovernorSettingsPacketID() (PKT_ECU_SETTINGS_GOVERNOR)
//! return the minimum encoded length for the ECU_GovernorSettings packet
#define getECU_GovernorSettingsMinDataLength() (19)
//! return the maximum encoded length for the ECU_GovernorSettings packet
#define getECU_GovernorSettingsMaxDataLength() (19)
/*!
* Throttle settings
*/
typedef struct
{
float kp; //!< Pump proportional gain
float ki; //!< Pump integral gain
float km; //!< Pump IMC (internal model) gain
float pressureLowerLimit; //!< Pump lower pressure limit (PSI)
float pressureUpperLimit; //!< Pump upper pressure limit (PSI)
float pressureSetpoint; //!< Fuel pressure setpoint
uint8_t minimumPWM;
uint8_t maximumPWM;
uint8_t rampRate; //!< Pump duty cycle ramp rate
ECU_PumpOptionBits_t options; //!< Pump control system options
uint8_t reservedA; //!< Reserved for future use
uint8_t reservedB; //!< Reserved for future use
}ECU_PumpSettings_t;
//! Create the ECU_PumpSettings packet
void encodeECU_PumpSettingsPacketStructure(void* pkt, const ECU_PumpSettings_t* user);
//! Decode the ECU_PumpSettings packet
int decodeECU_PumpSettingsPacketStructure(const void* pkt, ECU_PumpSettings_t* user);
//! return the packet ID for the ECU_PumpSettings packet
#define getECU_PumpSettingsPacketID() (PKT_ECU_SETTINGS_PUMP)
//! return the minimum encoded length for the ECU_PumpSettings packet
#define getECU_PumpSettingsMinDataLength() (30)
//! return the maximum encoded length for the ECU_PumpSettings packet
#define getECU_PumpSettingsMaxDataLength() (30)
/*!
* User data
*/
typedef struct
{
uint16_t powerCycles;
uint32_t engineTime;
uint32_t engineTimeTotal;
uint16_t fuelUsedOverflows;
uint8_t userValues[8];
}ECU_ECUData_t;
//! Create the ECU_ECUData packet
void encodeECU_ECUDataPacketStructure(void* pkt, const ECU_ECUData_t* user);
//! Decode the ECU_ECUData packet
int decodeECU_ECUDataPacketStructure(const void* pkt, ECU_ECUData_t* user);
//! return the packet ID for the ECU_ECUData packet
#define getECU_ECUDataPacketID() (PKT_ECU_SETTINGS_USER)
//! return the minimum encoded length for the ECU_ECUData packet
#define getECU_ECUDataMinDataLength() (20)
//! return the maximum encoded length for the ECU_ECUData packet
#define getECU_ECUDataMaxDataLength() (20)
#ifdef __cplusplus
}
#endif
#endif // _ECUSETTINGS_H

View File

@ -12,5 +12,7 @@
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* This license applies to all files in this directory.
*
* Author: Oliver Walters
*/