AP_PiccoloCAN: Provide compatibility for "Gen 2" Velociy ESC ICD

- The "Gen 2" Velocity ESC provides much more telemetry data
- The new ICD changes are compatible (i.e. legacy and modern ESCs can be on the CAN bus at the same time)
- Decode legacy packets and convert them to modern data structures
- Supports decoding of newer telemetry packets
- Supports decoding of new warning / error packets
This commit is contained in:
Oliver Walters 2020-09-24 16:40:33 +10:00 committed by Andrew Tridgell
parent 3e3da61396
commit 6786e832a1
25 changed files with 7679 additions and 1475 deletions

View File

@ -280,12 +280,12 @@ void AP_PiccoloCAN::update()
if (esc.newTelemetry) {
logger->Write_ESC(i, timestamp,
(int32_t) esc.statusA.rpm * 100,
esc.statusB.voltage,
esc.statusB.current,
(int16_t) esc.statusB.escTemperature,
(int32_t) esc.rpm * 100,
esc.voltage,
esc.current,
(int16_t) esc.fetTemperature,
0, // TODO - Accumulated current
(int16_t) esc.statusB.motorTemperature);
(int16_t) esc.motorTemperature);
esc.newTelemetry = false;
}
@ -321,11 +321,11 @@ void AP_PiccoloCAN::send_esc_telemetry_mavlink(uint8_t mav_chan)
if (is_esc_present(ii)) {
dataAvailable = true;
temperature[idx] = esc.statusB.escTemperature;
voltage[idx] = esc.statusB.voltage;
current[idx] = esc.statusB.current;
temperature[idx] = esc.fetTemperature;
voltage[idx] = esc.voltage;
current[idx] = esc.current;
totalcurrent[idx] = 0;
rpm[idx] = esc.statusA.rpm;
rpm[idx] = esc.rpm;
count[idx] = 0;
} else {
temperature[idx] = 0;
@ -475,10 +475,47 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
bool result = true;
/*
* The STATUS_A packet has slight variations between Gen-1 and Gen-2 ESCs.
* We can differentiate between the different versions,
* and coerce the "legacy" values into the modern values
* Legacy STATUS_A packet variables
*/
ESC_LegacyStatusBits_t legacyStatus;
ESC_LegacyWarningBits_t legacyWarnings;
ESC_LegacyErrorBits_t legacyErrors;
// Throw the packet against each decoding routine
if (decodeESC_StatusAPacketStructure(&frame, &esc.statusA)) {
if (decodeESC_StatusAPacket(&frame, &esc.mode, &esc.status, &esc.setpoint, &esc.rpm)) {
esc.newTelemetry = true;
} else if (decodeESC_StatusBPacketStructure(&frame, &esc.statusB)) {
} else if (decodeESC_LegacyStatusAPacket(&frame, &esc.mode, &legacyStatus, &legacyWarnings, &legacyErrors, &esc.setpoint, &esc.rpm)) {
// The status / warning / error bits need to be converted to modern values
// Note: Not *all* of the modern status bits are available in the Gen-1 packet
esc.status.hwInhibit = legacyStatus.hwInhibit;
esc.status.swInhibit = legacyStatus.swInhibit;
esc.status.afwEnabled = legacyStatus.afwEnabled;
esc.status.direction = legacyStatus.timeout;
esc.status.timeout = legacyStatus.timeout;
esc.status.starting = legacyStatus.starting;
esc.status.commandSource = legacyStatus.commandSource;
esc.status.running = legacyStatus.running;
// Copy the legacy warning information across
esc.warnings.overspeed = legacyWarnings.overspeed;
esc.warnings.overcurrent = legacyWarnings.overcurrent;
esc.warnings.escTemperature = legacyWarnings.escTemperature;
esc.warnings.motorTemperature = legacyWarnings.motorTemperature;
esc.warnings.undervoltage = legacyWarnings.undervoltage;
esc.warnings.overvoltage = legacyWarnings.overvoltage;
esc.warnings.invalidPWMsignal = legacyWarnings.invalidPWMsignal;
esc.warnings.settingsChecksum = legacyErrors.settingsChecksum;
// There are no common error bits between the Gen-1 and Gen-2 ICD
} else if (decodeESC_StatusBPacket(&frame, &esc.voltage, &esc.current, &esc.dutyCycle, &esc.escTemperature, &esc.motorTemperature)) {
esc.newTelemetry = true;
} else if (decodeESC_StatusCPacket(&frame, &esc.fetTemperature, &esc.pwmFrequency, &esc.timingAdvance)) {
esc.newTelemetry = true;
} else if (decodeESC_WarningErrorStatusPacket(&frame, &esc.warnings, &esc.errors)) {
esc.newTelemetry = true;
} else if (decodeESC_FirmwarePacketStructure(&frame, &esc.firmware)) {
// TODO
@ -564,7 +601,7 @@ bool AP_PiccoloCAN::is_esc_enabled(uint8_t chan)
PiccoloESC_Info_t &esc = _esc_info[chan];
if (esc.statusA.status.hwInhibit || esc.statusA.status.swInhibit) {
if (esc.status.hwInhibit || esc.status.swInhibit) {
return false;
}
@ -589,7 +626,7 @@ bool AP_PiccoloCAN::pre_arm_check(char* reason, uint8_t reason_len)
PiccoloESC_Info_t &esc = _esc_info[ii];
if (esc.statusA.status.hwInhibit) {
if (esc.status.hwInhibit) {
snprintf(reason, reason_len, "ESC %u is hardware inhibited", (ii + 1));
return false;
}

View File

@ -24,6 +24,7 @@
#include <AP_Param/AP_Param.h>
#include "piccolo_protocol/ESCPackets.h"
#include "piccolo_protocol/LegacyESCPackets.h"
// maximum number of ESC allowed on CAN bus simultaneously
#define PICCOLO_CAN_MAX_NUM_ESC 12
@ -119,9 +120,28 @@ private:
struct PiccoloESC_Info_t {
// ESC telemetry information
ESC_StatusA_t statusA; //! Telemetry data
ESC_StatusB_t statusB; //! Telemetry data
/* Telemetry data provided in the PKT_ESC_STATUS_A packet */
uint8_t mode; //! ESC operational mode
ESC_StatusBits_t status; //! ESC status information
uint16_t setpoint; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
/* Telemetry data provided in the PKT_ESC_STATUS_B packet */
uint16_t voltage; //!< ESC Rail Voltage
int16_t current; //!< ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
uint16_t dutyCycle; //!< ESC Motor Duty Cycle
int8_t escTemperature; //!< ESC Logic Board Temperature
uint8_t motorTemperature; //!< ESC Motor Temperature
/* Telemetry data provided in the PKT_ESC_STATUS_C packet */
float fetTemperature; //!< ESC Phase Board Temperature
uint16_t pwmFrequency; //!< Current motor PWM frequency (10 Hz per bit)
uint16_t timingAdvance; //!< Current timing advance (0.1 degree per bit)
/* ESC status information provided in the PKT_ESC_WARNINGS_ERRORS packet */
ESC_WarningBits_t warnings; //! ESC warning information
ESC_ErrorBits_t errors; //! ESC error information
ESC_Firmware_t firmware; //! Firmware / checksum information
ESC_Address_t address; //! Serial number
ESC_EEPROMSettings_t eeprom; //! Non-volatile settings info

View File

@ -0,0 +1,565 @@
// ESCCommands.c was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#include "ESCCommands.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Create the ESC_SetNodeID packet
*
* Set the CAN Node ID of the target ESC
* \param _pg_pkt points to the packet which will be created by this function
* \param serialNumber is The serial number must match that of the target ESC for the command to be accepted
* \param nodeID is The new Node ID of the ESC
*/
void encodeESC_SetNodeIDPacket(void* _pg_pkt, uint32_t serialNumber, uint8_t nodeID)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_SET_NODE_ID), _pg_data, &_pg_byteindex);
// The serial number must match that of the target ESC for the command to be accepted
// Range of serialNumber is 0 to 4294967295.
uint32ToBeBytes(serialNumber, _pg_data, &_pg_byteindex);
// The new Node ID of the ESC
// Range of nodeID is 0 to 255.
uint8ToBytes(nodeID, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SetNodeIDPacketID());
}// encodeESC_SetNodeIDPacket
/*!
* \brief Decode the ESC_SetNodeID packet
*
* Set the CAN Node ID of the target ESC
* \param _pg_pkt points to the packet being decoded by this function
* \param serialNumber receives The serial number must match that of the target ESC for the command to be accepted
* \param nodeID receives The new Node ID of the ESC
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_SetNodeIDPacket(const void* _pg_pkt, uint32_t* serialNumber, uint8_t* nodeID)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_SetNodeIDPacketID())
return 0;
if(_pg_numbytes < getESC_SetNodeIDMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_SET_NODE_ID)
return 0;
// The serial number must match that of the target ESC for the command to be accepted
// Range of serialNumber is 0 to 4294967295.
(*serialNumber) = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// The new Node ID of the ESC
// Range of nodeID is 0 to 255.
(*nodeID) = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_SetNodeIDPacket
/*!
* \brief Create the ESC_SetUserIDA packet
*
* Set User ID A
* \param _pg_pkt points to the packet which will be created by this function
* \param id is
*/
void encodeESC_SetUserIDAPacket(void* _pg_pkt, uint16_t id)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_SET_USER_ID_A), _pg_data, &_pg_byteindex);
// Range of id is 0 to 65535.
uint16ToBeBytes(id, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SetUserIDAPacketID());
}// encodeESC_SetUserIDAPacket
/*!
* \brief Decode the ESC_SetUserIDA packet
*
* Set User ID A
* \param _pg_pkt points to the packet being decoded by this function
* \param id receives
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_SetUserIDAPacket(const void* _pg_pkt, uint16_t* id)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_SetUserIDAPacketID())
return 0;
if(_pg_numbytes < getESC_SetUserIDAMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_SET_USER_ID_A)
return 0;
// Range of id is 0 to 65535.
(*id) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_SetUserIDAPacket
/*!
* \brief Create the ESC_SetUserIDB packet
*
* Set User ID B
* \param _pg_pkt points to the packet which will be created by this function
* \param id is
*/
void encodeESC_SetUserIDBPacket(void* _pg_pkt, uint16_t id)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_SET_USER_ID_B), _pg_data, &_pg_byteindex);
// Range of id is 0 to 65535.
uint16ToBeBytes(id, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SetUserIDBPacketID());
}// encodeESC_SetUserIDBPacket
/*!
* \brief Decode the ESC_SetUserIDB packet
*
* Set User ID B
* \param _pg_pkt points to the packet being decoded by this function
* \param id receives
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_SetUserIDBPacket(const void* _pg_pkt, uint16_t* id)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_SetUserIDBPacketID())
return 0;
if(_pg_numbytes < getESC_SetUserIDBMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_SET_USER_ID_B)
return 0;
// Range of id is 0 to 65535.
(*id) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_SetUserIDBPacket
/*!
* \brief Create the ESC_UnlockSettings packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_UnlockSettingsPacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_UNLOCK_SETTINGS), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0xA0), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0xB0), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0xC0), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_UnlockSettingsPacketID());
}// encodeESC_UnlockSettingsPacket
/*!
* \brief Decode the ESC_UnlockSettings packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_UnlockSettingsPacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_UnlockSettingsPacketID())
return 0;
if(_pg_numbytes < getESC_UnlockSettingsMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_UNLOCK_SETTINGS)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xA0)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xB0)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xC0)
return 0;
return 1;
}// decodeESC_UnlockSettingsPacket
/*!
* \brief Create the ESC_LockSettings packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_LockSettingsPacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_LOCK_SETTINGS), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0x0A), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0x0B), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0x0C), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_LockSettingsPacketID());
}// encodeESC_LockSettingsPacket
/*!
* \brief Decode the ESC_LockSettings packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_LockSettingsPacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_LockSettingsPacketID())
return 0;
if(_pg_numbytes < getESC_LockSettingsMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_LOCK_SETTINGS)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x0A)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x0B)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x0C)
return 0;
return 1;
}// decodeESC_LockSettingsPacket
/*!
* \brief Create the ESC_ValidateSettings packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_ValidateSettingsPacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_VALIDATE_SETTINGS), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0x1A), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0x2B), _pg_data, &_pg_byteindex);
uint8ToBytes((uint8_t)(0x3C), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_ValidateSettingsPacketID());
}// encodeESC_ValidateSettingsPacket
/*!
* \brief Decode the ESC_ValidateSettings packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_ValidateSettingsPacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_ValidateSettingsPacketID())
return 0;
if(_pg_numbytes < getESC_ValidateSettingsMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_VALIDATE_SETTINGS)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x1A)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x2B)
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x3C)
return 0;
return 1;
}// decodeESC_ValidateSettingsPacket
/*!
* \brief Create the ESC_ResetMotorRunTime packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet which will be created by this function
* \param serialNumber is Serial number must match ESC
*/
void encodeESC_ResetMotorRunTimePacket(void* _pg_pkt, uint16_t serialNumber)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_RESET_MOTOR_RUN_TIME), _pg_data, &_pg_byteindex);
// This byte is required for the command to be accepted
uint8ToBytes((uint8_t)(0xAB), _pg_data, &_pg_byteindex);
// This byte is required for the command to be accepted
uint8ToBytes((uint8_t)(0xCD), _pg_data, &_pg_byteindex);
// Serial number must match ESC
// Range of serialNumber is 0 to 65535.
uint16ToBeBytes(serialNumber, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_ResetMotorRunTimePacketID());
}// encodeESC_ResetMotorRunTimePacket
/*!
* \brief Decode the ESC_ResetMotorRunTime packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet being decoded by this function
* \param serialNumber receives Serial number must match ESC
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_ResetMotorRunTimePacket(const void* _pg_pkt, uint16_t* serialNumber)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_ResetMotorRunTimePacketID())
return 0;
if(_pg_numbytes < getESC_ResetMotorRunTimeMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_RESET_MOTOR_RUN_TIME)
return 0;
// This byte is required for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xAB)
return 0;
// This byte is required for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCD)
return 0;
// Serial number must match ESC
// Range of serialNumber is 0 to 65535.
(*serialNumber) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_ResetMotorRunTimePacket
/*!
* \brief Create the ESC_EnterBootloader packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_EnterBootloaderPacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_ENTER_BOOTLOADER), _pg_data, &_pg_byteindex);
// This byte is required for the command to be accepted
uint8ToBytes((uint8_t)(0xAA), _pg_data, &_pg_byteindex);
// This byte is required for the command to be accepted
uint8ToBytes((uint8_t)(0x55), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_EnterBootloaderPacketID());
}// encodeESC_EnterBootloaderPacket
/*!
* \brief Decode the ESC_EnterBootloader packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_EnterBootloaderPacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_EnterBootloaderPacketID())
return 0;
if(_pg_numbytes < getESC_EnterBootloaderMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_ENTER_BOOTLOADER)
return 0;
// This byte is required for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xAA)
return 0;
// This byte is required for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x55)
return 0;
return 1;
}// decodeESC_EnterBootloaderPacket
/*!
* \brief Create the ESC_ResetESC packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_ResetESCPacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_RESET), _pg_data, &_pg_byteindex);
// This byte is required for the command to be accepted
uint8ToBytes((uint8_t)(0xAA), _pg_data, &_pg_byteindex);
// This byte is required for the command to be accepted
uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_ResetESCPacketID());
}// encodeESC_ResetESCPacket
/*!
* \brief Decode the ESC_ResetESC packet
*
* Send a configuration command to the ESC (followed by optional command data
* bytes)
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_ResetESCPacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_ResetESCPacketID())
return 0;
if(_pg_numbytes < getESC_ResetESCMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_RESET)
return 0;
// This byte is required for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xAA)
return 0;
// This byte is required for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC)
return 0;
return 1;
}// decodeESC_ResetESCPacket
// end of ESCCommands.c

View File

@ -0,0 +1,172 @@
// ESCCommands.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _ESCCOMMANDS_H
#define _ESCCOMMANDS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
/*!
* Set the CAN Node ID of the target ESC
*/
typedef struct
{
uint32_t serialNumber; //!< The serial number must match that of the target ESC for the command to be accepted
uint8_t nodeID; //!< The new Node ID of the ESC
}ESC_SetNodeID_t;
//! Create the ESC_SetNodeID packet from parameters
void encodeESC_SetNodeIDPacket(void* pkt, uint32_t serialNumber, uint8_t nodeID);
//! Decode the ESC_SetNodeID packet to parameters
int decodeESC_SetNodeIDPacket(const void* pkt, uint32_t* serialNumber, uint8_t* nodeID);
//! return the packet ID for the ESC_SetNodeID packet
#define getESC_SetNodeIDPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_SetNodeID packet
#define getESC_SetNodeIDMinDataLength() (6)
//! return the maximum encoded length for the ESC_SetNodeID packet
#define getESC_SetNodeIDMaxDataLength() (6)
//! Create the ESC_SetUserIDA packet from parameters
void encodeESC_SetUserIDAPacket(void* pkt, uint16_t id);
//! Decode the ESC_SetUserIDA packet to parameters
int decodeESC_SetUserIDAPacket(const void* pkt, uint16_t* id);
//! return the packet ID for the ESC_SetUserIDA packet
#define getESC_SetUserIDAPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_SetUserIDA packet
#define getESC_SetUserIDAMinDataLength() (3)
//! return the maximum encoded length for the ESC_SetUserIDA packet
#define getESC_SetUserIDAMaxDataLength() (3)
//! Create the ESC_SetUserIDB packet from parameters
void encodeESC_SetUserIDBPacket(void* pkt, uint16_t id);
//! Decode the ESC_SetUserIDB packet to parameters
int decodeESC_SetUserIDBPacket(const void* pkt, uint16_t* id);
//! return the packet ID for the ESC_SetUserIDB packet
#define getESC_SetUserIDBPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_SetUserIDB packet
#define getESC_SetUserIDBMinDataLength() (3)
//! return the maximum encoded length for the ESC_SetUserIDB packet
#define getESC_SetUserIDBMaxDataLength() (3)
//! Create the ESC_UnlockSettings packet from parameters
void encodeESC_UnlockSettingsPacket(void* pkt);
//! Decode the ESC_UnlockSettings packet to parameters
int decodeESC_UnlockSettingsPacket(const void* pkt);
//! return the packet ID for the ESC_UnlockSettings packet
#define getESC_UnlockSettingsPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_UnlockSettings packet
#define getESC_UnlockSettingsMinDataLength() (4)
//! return the maximum encoded length for the ESC_UnlockSettings packet
#define getESC_UnlockSettingsMaxDataLength() (4)
//! Create the ESC_LockSettings packet from parameters
void encodeESC_LockSettingsPacket(void* pkt);
//! Decode the ESC_LockSettings packet to parameters
int decodeESC_LockSettingsPacket(const void* pkt);
//! return the packet ID for the ESC_LockSettings packet
#define getESC_LockSettingsPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_LockSettings packet
#define getESC_LockSettingsMinDataLength() (4)
//! return the maximum encoded length for the ESC_LockSettings packet
#define getESC_LockSettingsMaxDataLength() (4)
//! Create the ESC_ValidateSettings packet from parameters
void encodeESC_ValidateSettingsPacket(void* pkt);
//! Decode the ESC_ValidateSettings packet to parameters
int decodeESC_ValidateSettingsPacket(const void* pkt);
//! return the packet ID for the ESC_ValidateSettings packet
#define getESC_ValidateSettingsPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_ValidateSettings packet
#define getESC_ValidateSettingsMinDataLength() (4)
//! return the maximum encoded length for the ESC_ValidateSettings packet
#define getESC_ValidateSettingsMaxDataLength() (4)
//! Create the ESC_ResetMotorRunTime packet from parameters
void encodeESC_ResetMotorRunTimePacket(void* pkt, uint16_t serialNumber);
//! Decode the ESC_ResetMotorRunTime packet to parameters
int decodeESC_ResetMotorRunTimePacket(const void* pkt, uint16_t* serialNumber);
//! return the packet ID for the ESC_ResetMotorRunTime packet
#define getESC_ResetMotorRunTimePacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_ResetMotorRunTime packet
#define getESC_ResetMotorRunTimeMinDataLength() (5)
//! return the maximum encoded length for the ESC_ResetMotorRunTime packet
#define getESC_ResetMotorRunTimeMaxDataLength() (5)
//! Create the ESC_EnterBootloader packet from parameters
void encodeESC_EnterBootloaderPacket(void* pkt);
//! Decode the ESC_EnterBootloader packet to parameters
int decodeESC_EnterBootloaderPacket(const void* pkt);
//! return the packet ID for the ESC_EnterBootloader packet
#define getESC_EnterBootloaderPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_EnterBootloader packet
#define getESC_EnterBootloaderMinDataLength() (3)
//! return the maximum encoded length for the ESC_EnterBootloader packet
#define getESC_EnterBootloaderMaxDataLength() (3)
//! Create the ESC_ResetESC packet from parameters
void encodeESC_ResetESCPacket(void* pkt);
//! Decode the ESC_ResetESC packet to parameters
int decodeESC_ResetESCPacket(const void* pkt);
//! return the packet ID for the ESC_ResetESC packet
#define getESC_ResetESCPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_ResetESC packet
#define getESC_ResetESCMinDataLength() (3)
//! return the maximum encoded length for the ESC_ResetESC packet
#define getESC_ResetESCMaxDataLength() (3)
#ifdef __cplusplus
}
#endif
#endif // _ESCCOMMANDS_H

View File

@ -1,18 +1,9 @@
// ESCDefines.c was generated by ProtoGen version 2.18.c
// ESCDefines.c was generated by ProtoGen version 3.2.a
/*
This program 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 program 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/>.
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
@ -23,7 +14,7 @@
#include "scaledencode.h"
/*!
* \brief Encode a ESC_StatusBits_t structure into a byte array
* \brief Encode a ESC_StatusBits_t into a byte array
*
* The *status* of the ESC is represented using these status bits. ESC system
* functionality can be quickly determined using these bits
@ -35,73 +26,123 @@ void encodeESC_StatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Sta
{
int _pg_byteindex = *_pg_bytecount;
// 1 = Hardware inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->hwInhibit << 7;
// Set if hardware inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->hwInhibit == true) ? 1 : 0) << 7;
// 1 = Software inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->swInhibit << 6;
// Set if software inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->swInhibit == true) ? 1 : 0) << 6;
// 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->afwEnabled << 5;
// Set if Active Freewheeling is currently active
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->afwEnabled == true) ? 1 : 0) << 5;
// 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->direction << 4;
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->direction, 1) << 4;
// Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->timeout << 3;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->timeout == true) ? 1 : 0) << 3;
// 1 = in starting mode (0 = stopped or running)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->starting << 2;
// Set if ESC is in starting mode (Cleared if ESC is stopped or running)
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->starting == true) ? 1 : 0) << 2;
// 0 = most recent command from CAN, 1 = most recent command from PWM
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->commandSource << 1;
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->commandSource, 1) << 1;
// ESC is running
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->running;
_pg_byteindex += 1; // close bit field
// Set if ESC is running
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->running == true) ? 1 : 0);
// Warning active - refer to the PKT_ESC_WARNINGS_ERRORS packet
_pg_data[_pg_byteindex + 1] = (uint8_t)((_pg_user->anyWarnings == true) ? 1 : 0) << 7;
// Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->anyErrors == true) ? 1 : 0) << 6;
// Reserved bits for future use
// Set if the motor is spinning (even if it is not being driven)
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->spinning == true) ? 1 : 0);
// Set if motor is spinning opposite to configured rotation direction
_pg_data[_pg_byteindex + 2] = (uint8_t)((_pg_user->spinningReversed == true) ? 1 : 0) << 7;
// Set if motor duty cycle is being limited due to ESC protection settings
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->foldback == true) ? 1 : 0) << 6;
// Set if the ESC is attempting to sync with the motor
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->syncing == true) ? 1 : 0) << 5;
// Reserved bits for future use
// Set if the ESC is in debug mode (factory use only)
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->debug == true) ? 1 : 0);
_pg_byteindex += 3; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_StatusBits_t
/*!
* \brief Decode a ESC_StatusBits_t structure from a byte array
* \brief Decode a ESC_StatusBits_t from a byte array
*
* The *status* of the ESC is represented using these status bits. ESC system
* functionality can be quickly determined using these bits
* \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. If 0 is returned _pg_bytecount will not be updated.
* \return 1 if the data are decoded, else 0.
*/
int decodeESC_StatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_StatusBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = Hardware inhibit is active (ESC is disabled)
_pg_user->hwInhibit = (_pg_data[_pg_byteindex] >> 7);
// Set if hardware inhibit is active (ESC is disabled)
_pg_user->hwInhibit = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// 1 = Software inhibit is active (ESC is disabled)
_pg_user->swInhibit = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// Set if software inhibit is active (ESC is disabled)
_pg_user->swInhibit = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
_pg_user->afwEnabled = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// Set if Active Freewheeling is currently active
_pg_user->afwEnabled = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
_pg_user->direction = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
_pg_user->timeout = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
_pg_user->timeout = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// 1 = in starting mode (0 = stopped or running)
_pg_user->starting = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// Set if ESC is in starting mode (Cleared if ESC is stopped or running)
_pg_user->starting = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
// 0 = most recent command from CAN, 1 = most recent command from PWM
_pg_user->commandSource = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// ESC is running
_pg_user->running = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
// Set if ESC is running
_pg_user->running = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
// Warning active - refer to the PKT_ESC_WARNINGS_ERRORS packet
_pg_user->anyWarnings = ((_pg_data[_pg_byteindex + 1] >> 7)) ? true : false;
// Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet
_pg_user->anyErrors = (((_pg_data[_pg_byteindex + 1] >> 6) & 0x1)) ? true : false;
// Reserved bits for future use
// Set if the motor is spinning (even if it is not being driven)
_pg_user->spinning = (((_pg_data[_pg_byteindex + 1]) & 0x1)) ? true : false;
// Set if motor is spinning opposite to configured rotation direction
_pg_user->spinningReversed = ((_pg_data[_pg_byteindex + 2] >> 7)) ? true : false;
// Set if motor duty cycle is being limited due to ESC protection settings
_pg_user->foldback = (((_pg_data[_pg_byteindex + 2] >> 6) & 0x1)) ? true : false;
// Set if the ESC is attempting to sync with the motor
_pg_user->syncing = (((_pg_data[_pg_byteindex + 2] >> 5) & 0x1)) ? true : false;
// Reserved bits for future use
// Set if the ESC is in debug mode (factory use only)
_pg_user->debug = (((_pg_data[_pg_byteindex + 2]) & 0x1)) ? true : false;
_pg_byteindex += 3; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -110,14 +151,14 @@ int decodeESC_StatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Stat
}// decodeESC_StatusBits_t
/*!
* \brief Encode a ESC_WarningBits_t structure into a byte array
* \brief Encode a ESC_WarningBits_t into a byte array
*
* The *warning* bits enumerate various system warnings/errors of which the user
* (or user software) should be made aware. These *warning* bits are transmitted
* in the telemetry packets such that user software is aware of any these
* *warning* conditions and can poll the ESC for particular packets if any
* further information is needed. The ESC will continue to function in the case
* of a *warning* state
* The *warning* bits enumerate various system warnings/errors of which the
* user (or user software) should be made aware. These *warning* bits are
* transmitted in the telemetry packets such that user software is aware of any
* these *warning* conditions and can poll the ESC for particular packets if
* any further information is needed. The ESC will continue to function in the
* case of a *warning* state
* \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
@ -126,77 +167,122 @@ void encodeESC_WarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Wa
{
int _pg_byteindex = *_pg_bytecount;
// Set if RPM signal is not detected
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->noRPMSignal << 7;
// Reserved for future use
_pg_data[_pg_byteindex] = 0;
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overspeed << 6;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overspeed == true) ? 1 : 0) << 6;
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overcurrent << 5;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overcurrent == true) ? 1 : 0) << 5;
// Set if the internal ESC temperature is above the warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->escTemperature << 4;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->escTemperature == true) ? 1 : 0) << 4;
// Set if the motor temperature is above the warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->motorTemperature << 3;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->motorTemperature == true) ? 1 : 0) << 3;
// Set if the input voltage is below the minimum threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->undervoltage << 2;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->undervoltage == true) ? 1 : 0) << 2;
// Set if the input voltage is above the maximum threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overvoltage << 1;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overvoltage == true) ? 1 : 0) << 1;
// Set if hardware PWM input is enabled but invalid
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->invalidPWMsignal;
_pg_byteindex += 1; // close bit field
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->invalidPWMsignal == true) ? 1 : 0);
// Set if the motor demag angle exceeds the maximum threshold
_pg_data[_pg_byteindex + 1] = (uint8_t)((_pg_user->demagAngle == true) ? 1 : 0) << 7;
// Set if the auto-advance exceeds 25 degrees
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->advanceLimit == true) ? 1 : 0) << 6;
// Set if the measured demag pulse is exceptionally long
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->longDemag == true) ? 1 : 0) << 5;
// Set if a zero-crossing measurement was missed
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->missedZeroCrossing == true) ? 1 : 0) << 4;
// Motor is spinning in the wrong direction
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->spinningReversed == true) ? 1 : 0) << 3;
// Motor has reached maximum allowable commutation speed
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->commSpeedLimit == true) ? 1 : 0) << 2;
// Settings checksum does not match programmed value
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->settingsChecksum == true) ? 1 : 0) << 1;
// Reserved for future use
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_WarningBits_t
/*!
* \brief Decode a ESC_WarningBits_t structure from a byte array
* \brief Decode a ESC_WarningBits_t from a byte array
*
* The *warning* bits enumerate various system warnings/errors of which the user
* (or user software) should be made aware. These *warning* bits are transmitted
* in the telemetry packets such that user software is aware of any these
* *warning* conditions and can poll the ESC for particular packets if any
* further information is needed. The ESC will continue to function in the case
* of a *warning* state
* The *warning* bits enumerate various system warnings/errors of which the
* user (or user software) should be made aware. These *warning* bits are
* transmitted in the telemetry packets such that user software is aware of any
* these *warning* conditions and can poll the ESC for particular packets if
* any further information is needed. The ESC will continue to function in the
* case of a *warning* state
* \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. If 0 is returned _pg_bytecount will not be updated.
* \return 1 if the data are decoded, else 0.
*/
int decodeESC_WarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_WarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if RPM signal is not detected
_pg_user->noRPMSignal = (_pg_data[_pg_byteindex] >> 7);
// Reserved for future use
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_user->overspeed = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
_pg_user->overspeed = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
_pg_user->overcurrent = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
_pg_user->overcurrent = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Set if the internal ESC temperature is above the warning threshold
_pg_user->escTemperature = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
_pg_user->escTemperature = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// Set if the motor temperature is above the warning threshold
_pg_user->motorTemperature = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
_pg_user->motorTemperature = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// Set if the input voltage is below the minimum threshold
_pg_user->undervoltage = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
_pg_user->undervoltage = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
// Set if the input voltage is above the maximum threshold
_pg_user->overvoltage = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
_pg_user->overvoltage = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// Set if hardware PWM input is enabled but invalid
_pg_user->invalidPWMsignal = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
_pg_user->invalidPWMsignal = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
// Set if the motor demag angle exceeds the maximum threshold
_pg_user->demagAngle = ((_pg_data[_pg_byteindex + 1] >> 7)) ? true : false;
// Set if the auto-advance exceeds 25 degrees
_pg_user->advanceLimit = (((_pg_data[_pg_byteindex + 1] >> 6) & 0x1)) ? true : false;
// Set if the measured demag pulse is exceptionally long
_pg_user->longDemag = (((_pg_data[_pg_byteindex + 1] >> 5) & 0x1)) ? true : false;
// Set if a zero-crossing measurement was missed
_pg_user->missedZeroCrossing = (((_pg_data[_pg_byteindex + 1] >> 4) & 0x1)) ? true : false;
// Motor is spinning in the wrong direction
_pg_user->spinningReversed = (((_pg_data[_pg_byteindex + 1] >> 3) & 0x1)) ? true : false;
// Motor has reached maximum allowable commutation speed
_pg_user->commSpeedLimit = (((_pg_data[_pg_byteindex + 1] >> 2) & 0x1)) ? true : false;
// Settings checksum does not match programmed value
_pg_user->settingsChecksum = (((_pg_data[_pg_byteindex + 1] >> 1) & 0x1)) ? true : false;
// Reserved for future use
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -205,7 +291,7 @@ int decodeESC_WarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_War
}// decodeESC_WarningBits_t
/*!
* \brief Encode a ESC_ErrorBits_t structure into a byte array
* \brief Encode a ESC_ErrorBits_t into a byte array
*
* The *error* bits enumerate critical system errors that will cause the ESC to
* stop functioning until the error cases are alleviated
@ -217,73 +303,76 @@ void encodeESC_ErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Erro
{
int _pg_byteindex = *_pg_bytecount;
// Set if communication link to the motor controller is lost
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->linkError << 7;
// Set if the ESC failed to start the motor
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->failedStart == true) ? 1 : 0) << 7;
// Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->foldback << 6;
// Lost commutation
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->commutation == true) ? 1 : 0) << 6;
// Set if the settings checksum does not match the programmed values
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->settingsChecksum << 5;
// Set if hall sensor error detected
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->hallSensor == true) ? 1 : 0) << 5;
// Set if the motor settings are invalid
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->motorSettings << 4;
// Current exceeded hard-limit
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overcurrent == true) ? 1 : 0) << 4;
// Temperature exceeded hard-limit
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overtemperature == true) ? 1 : 0) << 3;
// Motor commutation speed exceeded hard-limit
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overspeed == true) ? 1 : 0) << 2;
// Motor stopped due to high demag angle
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->demag == true) ? 1 : 0) << 1;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedD << 3;
_pg_data[_pg_byteindex + 1] = 0;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedE << 2;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedF << 1;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedG;
_pg_byteindex += 1; // close bit field
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_ErrorBits_t
/*!
* \brief Decode a ESC_ErrorBits_t structure from a byte array
* \brief Decode a ESC_ErrorBits_t from a byte array
*
* The *error* bits enumerate critical system errors that will cause the ESC to
* stop functioning until the error cases are alleviated
* \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. If 0 is returned _pg_bytecount will not be updated.
* \return 1 if the data are decoded, else 0.
*/
int decodeESC_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_ErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if communication link to the motor controller is lost
_pg_user->linkError = (_pg_data[_pg_byteindex] >> 7);
// Set if the ESC failed to start the motor
_pg_user->failedStart = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
_pg_user->foldback = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// Lost commutation
_pg_user->commutation = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Set if the settings checksum does not match the programmed values
_pg_user->settingsChecksum = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// Set if hall sensor error detected
_pg_user->hallSensor = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Set if the motor settings are invalid
_pg_user->motorSettings = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Current exceeded hard-limit
_pg_user->overcurrent = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// Temperature exceeded hard-limit
_pg_user->overtemperature = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// Motor commutation speed exceeded hard-limit
_pg_user->overspeed = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
// Motor stopped due to high demag angle
_pg_user->demag = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// Reserved for future use
_pg_user->reservedD = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// Reserved for future use
_pg_user->reservedE = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// Reserved for future use
_pg_user->reservedF = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// Reserved for future use
_pg_user->reservedG = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -292,7 +381,7 @@ int decodeESC_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Error
}// decodeESC_ErrorBits_t
/*!
* \brief Encode a ESC_TelemetryPackets_t structure into a byte array
* \brief Encode a ESC_TelemetryPackets_t into a byte array
*
* These bits are used to determine which packets are automatically transmitted
* as telemetry data by the ESC. Only the packets described here can be
@ -306,28 +395,28 @@ void encodeESC_TelemetryPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const E
int _pg_byteindex = *_pg_bytecount;
// If this bit is set, the STATUS_A packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->statusA << 7;
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->statusA == true) ? 1 : 0) << 7;
// If this bit is set, the STATUS_B packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->statusB << 6;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->statusB == true) ? 1 : 0) << 6;
// If this bit is set, the STATUS_C packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->statusC << 5;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->statusC == true) ? 1 : 0) << 5;
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->accelerometer << 4;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->accelerometer == true) ? 1 : 0) << 4;
// If this bit is set, the STATUS_D packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->statusD << 3;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->statusD == true) ? 1 : 0) << 3;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedB << 2;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->reservedTelemA == true) ? 1 : 0) << 2;
// If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->piccoloDownlink << 1;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piccoloDownlink == true) ? 1 : 0) << 1;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedD;
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->reservedTelemC == true) ? 1 : 0);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -335,7 +424,7 @@ void encodeESC_TelemetryPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const E
}// encodeESC_TelemetryPackets_t
/*!
* \brief Decode a ESC_TelemetryPackets_t structure from a byte array
* \brief Decode a ESC_TelemetryPackets_t from a byte array
*
* These bits are used to determine which packets are automatically transmitted
* as telemetry data by the ESC. Only the packets described here can be
@ -343,35 +432,35 @@ void encodeESC_TelemetryPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const E
* \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. If 0 is returned _pg_bytecount will not be updated.
* \return 1 if the data are decoded, else 0.
*/
int decodeESC_TelemetryPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_TelemetryPackets_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// If this bit is set, the STATUS_A packet will be transmitted at the configured rate
_pg_user->statusA = (_pg_data[_pg_byteindex] >> 7);
_pg_user->statusA = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// If this bit is set, the STATUS_B packet will be transmitted at the configured rate
_pg_user->statusB = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
_pg_user->statusB = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// If this bit is set, the STATUS_C packet will be transmitted at the configured rate
_pg_user->statusC = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
_pg_user->statusC = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_user->accelerometer = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
_pg_user->accelerometer = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// If this bit is set, the STATUS_D packet will be transmitted at the configured rate
_pg_user->statusD = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
_pg_user->statusD = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// Reserved for future use
_pg_user->reservedB = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
_pg_user->reservedTelemA = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
// If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
_pg_user->piccoloDownlink = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
_pg_user->piccoloDownlink = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// Reserved for future use
_pg_user->reservedD = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_user->reservedTelemC = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -381,27 +470,82 @@ int decodeESC_TelemetryPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ES
}// decodeESC_TelemetryPackets_t
/*!
* \brief Set a ESC_TelemetryPackets_t structure to initial values.
* \brief Encode a ESC_DebugPackets_t into a byte array
*
* Set a ESC_TelemetryPackets_t structure to initial values. Not all fields are set,
* only those which the protocol specifies.
* \param _pg_user is the structure whose data are set to initial values
* These bits are used to select which debug packets are transmitted at
* high-frequency by the ESC
* \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 initESC_TelemetryPackets_t(ESC_TelemetryPackets_t* _pg_user)
void encodeESC_DebugPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_DebugPackets_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// If this bit is set, the STATUS_A packet will be transmitted at the configured rate
_pg_user->statusA = 1;
// Control loop terms
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->ctrlLoopOutputs == true) ? 1 : 0) << 7;
// If this bit is set, the STATUS_B packet will be transmitted at the configured rate
_pg_user->statusB = 1;
// Hall sensor debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->hallSensors == true) ? 1 : 0) << 6;
// If this bit is set, the STATUS_C packet will be transmitted at the configured rate
_pg_user->statusC = 1;
// Commutation debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->commutation == true) ? 1 : 0) << 5;
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_user->accelerometer = 0;
// Demag debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->demag == true) ? 1 : 0) << 4;
}// initESC_TelemetryPackets_t
// PWM input debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->pwmInput == true) ? 1 : 0) << 3;
// Reserved for future use
_pg_byteindex += 1; // close bit field
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
}// encodeESC_DebugPackets_t
/*!
* \brief Decode a ESC_DebugPackets_t from a byte array
*
* These bits are used to select which debug packets are transmitted at
* high-frequency by the ESC
* \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 decodeESC_DebugPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_DebugPackets_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Control loop terms
_pg_user->ctrlLoopOutputs = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// Hall sensor debug information
_pg_user->hallSensors = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Commutation debug information
_pg_user->commutation = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Demag debug information
_pg_user->demag = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// PWM input debug information
_pg_user->pwmInput = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// Reserved for future use
_pg_byteindex += 1; // close bit field
// Reserved for future use
_pg_byteindex += 1;
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_DebugPackets_t
// end of ESCDefines.c

View File

@ -1,25 +1,16 @@
// ESCDefines.h was generated by ProtoGen version 2.18.c
// ESCDefines.h was generated by ProtoGen version 3.2.a
/*
This program 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 program 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/>.
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _ESCDEFINES_H
#define _ESCDEFINES_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
@ -28,6 +19,7 @@ extern "C" {
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
/*!
@ -36,52 +28,71 @@ extern "C" {
*/
typedef struct
{
unsigned hwInhibit : 1; //!< 1 = Hardware inhibit is active (ESC is disabled)
unsigned swInhibit : 1; //!< 1 = Software inhibit is active (ESC is disabled)
unsigned afwEnabled : 1; //!< 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
unsigned direction : 1; //!< 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
unsigned timeout : 1; //!< Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
unsigned starting : 1; //!< 1 = in starting mode (0 = stopped or running)
unsigned commandSource : 1; //!< 0 = most recent command from CAN, 1 = most recent command from PWM
unsigned running : 1; //!< ESC is running
bool hwInhibit; //!< Set if hardware inhibit is active (ESC is disabled)
bool swInhibit; //!< Set if software inhibit is active (ESC is disabled)
bool afwEnabled; //!< Set if Active Freewheeling is currently active
uint8_t direction; //!< 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
bool timeout; //!< Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
bool starting; //!< Set if ESC is in starting mode (Cleared if ESC is stopped or running)
uint8_t commandSource; //!< 0 = most recent command from CAN, 1 = most recent command from PWM
bool running; //!< Set if ESC is running
bool anyWarnings; //!< Warning active - refer to the PKT_ESC_WARNINGS_ERRORS packet
bool anyErrors; //!< Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet
bool spinning; //!< Set if the motor is spinning (even if it is not being driven)
bool spinningReversed; //!< Set if motor is spinning opposite to configured rotation direction
bool foldback; //!< Set if motor duty cycle is being limited due to ESC protection settings
bool syncing; //!< Set if the ESC is attempting to sync with the motor
bool debug; //!< Set if the ESC is in debug mode (factory use only)
}ESC_StatusBits_t;
//! return the minimum encoded length for the ESC_StatusBits_t structure
#define getMinLengthOfESC_StatusBits_t() (1)
#define getMinLengthOfESC_StatusBits_t() (3)
//! Encode a ESC_StatusBits_t structure into a byte array
//! return the maximum encoded length for the ESC_StatusBits_t structure
#define getMaxLengthOfESC_StatusBits_t() (3)
//! Encode a ESC_StatusBits_t into a byte array
void encodeESC_StatusBits_t(uint8_t* data, int* bytecount, const ESC_StatusBits_t* user);
//! Decode a ESC_StatusBits_t structure from a byte array
//! Decode a ESC_StatusBits_t from a byte array
int decodeESC_StatusBits_t(const uint8_t* data, int* bytecount, ESC_StatusBits_t* user);
/*!
* The *warning* bits enumerate various system warnings/errors of which the user
* (or user software) should be made aware. These *warning* bits are transmitted
* in the telemetry packets such that user software is aware of any these
* *warning* conditions and can poll the ESC for particular packets if any
* further information is needed. The ESC will continue to function in the case
* of a *warning* state
* The *warning* bits enumerate various system warnings/errors of which the
* user (or user software) should be made aware. These *warning* bits are
* transmitted in the telemetry packets such that user software is aware of any
* these *warning* conditions and can poll the ESC for particular packets if
* any further information is needed. The ESC will continue to function in the
* case of a *warning* state
*/
typedef struct
{
unsigned noRPMSignal : 1; //!< Set if RPM signal is not detected
unsigned overspeed : 1; //!< Set if the ESC motor speed exceeds the configured warning threshold
unsigned overcurrent : 1; //!< Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
unsigned escTemperature : 1; //!< Set if the internal ESC temperature is above the warning threshold
unsigned motorTemperature : 1; //!< Set if the motor temperature is above the warning threshold
unsigned undervoltage : 1; //!< Set if the input voltage is below the minimum threshold
unsigned overvoltage : 1; //!< Set if the input voltage is above the maximum threshold
unsigned invalidPWMsignal : 1; //!< Set if hardware PWM input is enabled but invalid
bool overspeed; //!< Set if the ESC motor speed exceeds the configured warning threshold
bool overcurrent; //!< Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
bool escTemperature; //!< Set if the internal ESC temperature is above the warning threshold
bool motorTemperature; //!< Set if the motor temperature is above the warning threshold
bool undervoltage; //!< Set if the input voltage is below the minimum threshold
bool overvoltage; //!< Set if the input voltage is above the maximum threshold
bool invalidPWMsignal; //!< Set if hardware PWM input is enabled but invalid
bool demagAngle; //!< Set if the motor demag angle exceeds the maximum threshold
bool advanceLimit; //!< Set if the auto-advance exceeds 25 degrees
bool longDemag; //!< Set if the measured demag pulse is exceptionally long
bool missedZeroCrossing; //!< Set if a zero-crossing measurement was missed
bool spinningReversed; //!< Motor is spinning in the wrong direction
bool commSpeedLimit; //!< Motor has reached maximum allowable commutation speed
bool settingsChecksum; //!< Settings checksum does not match programmed value
}ESC_WarningBits_t;
//! return the minimum encoded length for the ESC_WarningBits_t structure
#define getMinLengthOfESC_WarningBits_t() (1)
#define getMinLengthOfESC_WarningBits_t() (2)
//! Encode a ESC_WarningBits_t structure into a byte array
//! return the maximum encoded length for the ESC_WarningBits_t structure
#define getMaxLengthOfESC_WarningBits_t() (2)
//! Encode a ESC_WarningBits_t into a byte array
void encodeESC_WarningBits_t(uint8_t* data, int* bytecount, const ESC_WarningBits_t* user);
//! Decode a ESC_WarningBits_t structure from a byte array
//! Decode a ESC_WarningBits_t from a byte array
int decodeESC_WarningBits_t(const uint8_t* data, int* bytecount, ESC_WarningBits_t* user);
/*!
@ -90,23 +101,25 @@ int decodeESC_WarningBits_t(const uint8_t* data, int* bytecount, ESC_WarningBits
*/
typedef struct
{
unsigned linkError : 1; //!< Set if communication link to the motor controller is lost
unsigned foldback : 1; //!< Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
unsigned settingsChecksum : 1; //!< Set if the settings checksum does not match the programmed values
unsigned motorSettings : 1; //!< Set if the motor settings are invalid
unsigned reservedD : 1; //!< Reserved for future use
unsigned reservedE : 1; //!< Reserved for future use
unsigned reservedF : 1; //!< Reserved for future use
unsigned reservedG : 1; //!< Reserved for future use
bool failedStart; //!< Set if the ESC failed to start the motor
bool commutation; //!< Lost commutation
bool hallSensor; //!< Set if hall sensor error detected
bool overcurrent; //!< Current exceeded hard-limit
bool overtemperature; //!< Temperature exceeded hard-limit
bool overspeed; //!< Motor commutation speed exceeded hard-limit
bool demag; //!< Motor stopped due to high demag angle
}ESC_ErrorBits_t;
//! return the minimum encoded length for the ESC_ErrorBits_t structure
#define getMinLengthOfESC_ErrorBits_t() (1)
#define getMinLengthOfESC_ErrorBits_t() (2)
//! Encode a ESC_ErrorBits_t structure into a byte array
//! return the maximum encoded length for the ESC_ErrorBits_t structure
#define getMaxLengthOfESC_ErrorBits_t() (2)
//! Encode a ESC_ErrorBits_t into a byte array
void encodeESC_ErrorBits_t(uint8_t* data, int* bytecount, const ESC_ErrorBits_t* user);
//! Decode a ESC_ErrorBits_t structure from a byte array
//! Decode a ESC_ErrorBits_t from a byte array
int decodeESC_ErrorBits_t(const uint8_t* data, int* bytecount, ESC_ErrorBits_t* user);
/*!
@ -116,35 +129,54 @@ int decodeESC_ErrorBits_t(const uint8_t* data, int* bytecount, ESC_ErrorBits_t*
*/
typedef struct
{
unsigned statusA : 1; //!< If this bit is set, the STATUS_A packet will be transmitted at the configured rate
unsigned statusB : 1; //!< If this bit is set, the STATUS_B packet will be transmitted at the configured rate
unsigned statusC : 1; //!< If this bit is set, the STATUS_C packet will be transmitted at the configured rate
unsigned accelerometer : 1; //!< If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
unsigned statusD : 1; //!< If this bit is set, the STATUS_D packet will be transmitted at the configured rate
unsigned reservedB : 1; //!< Reserved for future use
unsigned piccoloDownlink : 1; //!< If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
unsigned reservedD : 1; //!< Reserved for future use
bool statusA; //!< If this bit is set, the STATUS_A packet will be transmitted at the configured rate
bool statusB; //!< If this bit is set, the STATUS_B packet will be transmitted at the configured rate
bool statusC; //!< If this bit is set, the STATUS_C packet will be transmitted at the configured rate
bool accelerometer; //!< If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
bool statusD; //!< If this bit is set, the STATUS_D packet will be transmitted at the configured rate
bool reservedTelemA; //!< Reserved for future use
bool piccoloDownlink; //!< If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
bool reservedTelemC; //!< Reserved for future use
}ESC_TelemetryPackets_t;
// Initial and verify values for TelemetryPackets
#define ESCVelocity_TelemetryPackets_statusA_InitValue 1
#define ESCVelocity_TelemetryPackets_statusB_InitValue 1
#define ESCVelocity_TelemetryPackets_statusC_InitValue 1
#define ESCVelocity_TelemetryPackets_accelerometer_InitValue 0
//! return the minimum encoded length for the ESC_TelemetryPackets_t structure
#define getMinLengthOfESC_TelemetryPackets_t() (1)
//! Encode a ESC_TelemetryPackets_t structure into a byte array
//! return the maximum encoded length for the ESC_TelemetryPackets_t structure
#define getMaxLengthOfESC_TelemetryPackets_t() (1)
//! Encode a ESC_TelemetryPackets_t into a byte array
void encodeESC_TelemetryPackets_t(uint8_t* data, int* bytecount, const ESC_TelemetryPackets_t* user);
//! Decode a ESC_TelemetryPackets_t structure from a byte array
//! Decode a ESC_TelemetryPackets_t from a byte array
int decodeESC_TelemetryPackets_t(const uint8_t* data, int* bytecount, ESC_TelemetryPackets_t* user);
//! Set a ESC_TelemetryPackets_t structure to initial values
void initESC_TelemetryPackets_t(ESC_TelemetryPackets_t* user);
/*!
* These bits are used to select which debug packets are transmitted at
* high-frequency by the ESC
*/
typedef struct
{
bool ctrlLoopOutputs; //!< Control loop terms
bool hallSensors; //!< Hall sensor debug information
bool commutation; //!< Commutation debug information
bool demag; //!< Demag debug information
bool pwmInput; //!< PWM input debug information
}ESC_DebugPackets_t;
//! return the minimum encoded length for the ESC_DebugPackets_t structure
#define getMinLengthOfESC_DebugPackets_t() (2)
//! return the maximum encoded length for the ESC_DebugPackets_t structure
#define getMaxLengthOfESC_DebugPackets_t() (2)
//! Encode a ESC_DebugPackets_t into a byte array
void encodeESC_DebugPackets_t(uint8_t* data, int* bytecount, const ESC_DebugPackets_t* user);
//! Decode a ESC_DebugPackets_t from a byte array
int decodeESC_DebugPackets_t(const uint8_t* data, int* bytecount, ESC_DebugPackets_t* user);
#ifdef __cplusplus
}
#endif
#endif
#endif // _ESCDEFINES_H

File diff suppressed because it is too large Load Diff

View File

@ -1,25 +1,16 @@
// ESCPackets.h was generated by ProtoGen version 2.18.c
// ESCPackets.h was generated by ProtoGen version 3.2.a
/*
This program 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 program 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/>.
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _ESCPACKETS_H
#define _ESCPACKETS_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
@ -28,49 +19,80 @@ extern "C" {
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
#include "ESCDefines.h"
/*!
* General ESC configuration parameters
*/
typedef struct
{
bool swInhibit; //!< 1 = ESC is inhibited (disabled) on startup
bool piccoloCommands; //!< 1 = ESC will respond to PICCOLO autopilot commands
bool broadcastCommands; //!< 1 = ESC will accept broadcast command messages
uint8_t commandInputPriority; //!< Command input source priority, refer to enumeration ESCCommandPriorities
uint8_t motorTempSensor; //!< External motor temperature sensor configuration
uint8_t keepalive; //!< ESC keepalive timeout - If this is non-zero, the ESC will automatically revert to *STANDBY* mode if it does not receive a valid command for the alloted period
uint8_t motorBeepMode;
uint8_t motorBeepVolume; //!< Motor beep volume
}ESC_Config_t;
//! Create the ESC_Config packet
void encodeESC_ConfigPacketStructure(void* pkt, const ESC_Config_t* user);
//! Decode the ESC_Config packet
int decodeESC_ConfigPacketStructure(const void* pkt, ESC_Config_t* user);
//! Create the ESC_Config packet from parameters
void encodeESC_ConfigPacket(void* pkt, bool swInhibit, bool piccoloCommands, bool broadcastCommands, uint8_t commandInputPriority, uint8_t motorTempSensor, uint8_t keepalive, uint8_t motorBeepMode, uint8_t motorBeepVolume);
//! Decode the ESC_Config packet to parameters
int decodeESC_ConfigPacket(const void* pkt, bool* swInhibit, bool* piccoloCommands, bool* broadcastCommands, uint8_t* commandInputPriority, uint8_t* motorTempSensor, uint8_t* keepalive, uint8_t* motorBeepMode, uint8_t* motorBeepVolume);
//! Encode a ESC_Config_t into a byte array
void encodeESC_Config_t(uint8_t* data, int* bytecount, const ESC_Config_t* user);
//! Decode a ESC_Config_t from a byte array
int decodeESC_Config_t(const uint8_t* data, int* bytecount, ESC_Config_t* user);
//! return the packet ID for the ESC_Config packet
#define getESC_ConfigPacketID() (PKT_ESC_CONFIG)
//! return the minimum encoded length for the ESC_Config packet
#define getESC_ConfigMinDataLength() (8)
//! return the maximum encoded length for the ESC_Config packet
#define getESC_ConfigMaxDataLength() (8)
/*!
* Telemetry settings (storage class)
*/
typedef struct
{
uint8_t period; //!< Telemetry period
uint8_t period; //!< Telemetry period code (maps indirectly to a telemetry period value)
uint8_t silence; //!< Telemetry silence period (delay after RESET before telemetry data is sent)
ESC_TelemetryPackets_t packets; //!< Bitfield describing which telemetry packets are enabled
}ESC_TelemetryConfig_t;
// Initial and verify values for TelemetryConfig
#define ESCVelocity_TelemetryConfig_period_InitValue 4
#define ESCVelocity_TelemetryConfig_period_VerifyMax 250
#define ESCVelocity_TelemetryConfig_silence_InitValue 20
#define ESCVelocity_TelemetryConfig_silence_VerifyMax 250
//! Encode a ESC_TelemetryConfig_t structure into a byte array
void encodeESC_TelemetryConfig_t(uint8_t* data, int* bytecount, const ESC_TelemetryConfig_t* user);
//! Decode a ESC_TelemetryConfig_t structure from a byte array
int decodeESC_TelemetryConfig_t(const uint8_t* data, int* bytecount, ESC_TelemetryConfig_t* user);
//! Set a ESC_TelemetryConfig_t structure to initial values
void initESC_TelemetryConfig_t(ESC_TelemetryConfig_t* user);
//! Verify a ESC_TelemetryConfig_t structure has acceptable values
int verifyESC_TelemetryConfig_t(ESC_TelemetryConfig_t* user);
//! Create the ESC_TelemetryConfig packet
void encodeESC_TelemetryConfigPacketStructure(void* pkt, const ESC_TelemetryConfig_t* user);
//! Decode the ESC_TelemetryConfig packet
int decodeESC_TelemetryConfigPacketStructure(const void* pkt, ESC_TelemetryConfig_t* user);
//! Create the ESC_TelemetryConfig packet
//! Create the ESC_TelemetryConfig packet from parameters
void encodeESC_TelemetryConfigPacket(void* pkt, uint8_t period, uint8_t silence, const ESC_TelemetryPackets_t* packets);
//! Decode the ESC_TelemetryConfig packet
//! Decode the ESC_TelemetryConfig packet to parameters
int decodeESC_TelemetryConfigPacket(const void* pkt, uint8_t* period, uint8_t* silence, ESC_TelemetryPackets_t* packets);
//! Encode a ESC_TelemetryConfig_t into a byte array
void encodeESC_TelemetryConfig_t(uint8_t* data, int* bytecount, const ESC_TelemetryConfig_t* user);
//! Decode a ESC_TelemetryConfig_t from a byte array
int decodeESC_TelemetryConfig_t(const uint8_t* data, int* bytecount, ESC_TelemetryConfig_t* user);
//! return the packet ID for the ESC_TelemetryConfig packet
#define getESC_TelemetryConfigPacketID() (PKT_ESC_TELEMETRY_SETTINGS)
@ -95,10 +117,10 @@ typedef struct
uint16_t pwmValueD; //!< The PWM (pulse width) command for ESC with CAN ID 4
}ESC_CommandMultipleESCs_t;
//! Create the ESC_CommandMultipleESCs packet
//! Create the ESC_CommandMultipleESCs packet from parameters
void encodeESC_CommandMultipleESCsPacket(void* pkt, uint16_t pwmValueA, uint16_t pwmValueB, uint16_t pwmValueC, uint16_t pwmValueD, uint32_t id);
//! Decode the ESC_CommandMultipleESCs packet
//! Decode the ESC_CommandMultipleESCs packet to parameters
int decodeESC_CommandMultipleESCsPacket(const void* pkt, uint16_t* pwmValueA, uint16_t* pwmValueB, uint16_t* pwmValueC, uint16_t* pwmValueD);
//! return the minimum encoded length for the ESC_CommandMultipleESCs packet
@ -107,10 +129,10 @@ int decodeESC_CommandMultipleESCsPacket(const void* pkt, uint16_t* pwmValueA, ui
//! return the maximum encoded length for the ESC_CommandMultipleESCs packet
#define getESC_CommandMultipleESCsMaxDataLength() (8)
//! Create the ESC_Disable packet
//! Create the ESC_Disable packet from parameters
void encodeESC_DisablePacket(void* pkt);
//! Decode the ESC_Disable packet
//! Decode the ESC_Disable packet to parameters
int decodeESC_DisablePacket(const void* pkt);
//! return the packet ID for the ESC_Disable packet
@ -122,10 +144,10 @@ int decodeESC_DisablePacket(const void* pkt);
//! return the maximum encoded length for the ESC_Disable packet
#define getESC_DisableMaxDataLength() (2)
//! Create the ESC_Enable packet
//! Create the ESC_Enable packet from parameters
void encodeESC_EnablePacket(void* pkt);
//! Decode the ESC_Enable packet
//! Decode the ESC_Enable packet to parameters
int decodeESC_EnablePacket(const void* pkt);
//! return the packet ID for the ESC_Enable packet
@ -137,10 +159,20 @@ int decodeESC_EnablePacket(const void* pkt);
//! return the maximum encoded length for the ESC_Enable packet
#define getESC_EnableMaxDataLength() (2)
//! Create the ESC_PWMCommand packet
/*!
* Send a PWM (pulse width) command to an individual ESC. The pulse width value
* in specified in microseconds for compatibility with standard ESC interface.
* Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus.
*/
typedef struct
{
uint16_t pwmCommand; //!< PWM command
}ESC_PWMCommand_t;
//! Create the ESC_PWMCommand packet from parameters
void encodeESC_PWMCommandPacket(void* pkt, uint16_t pwmCommand);
//! Decode the ESC_PWMCommand packet
//! Decode the ESC_PWMCommand packet to parameters
int decodeESC_PWMCommandPacket(const void* pkt, uint16_t* pwmCommand);
//! return the packet ID for the ESC_PWMCommand packet
@ -152,10 +184,19 @@ int decodeESC_PWMCommandPacket(const void* pkt, uint16_t* pwmCommand);
//! return the maximum encoded length for the ESC_PWMCommand packet
#define getESC_PWMCommandMaxDataLength() (2)
//! Create the ESC_RPMCommand packet
/*!
* Send an RPM (speed) command to an individual ESC. Use the broadcast ID
* (0xFF) to send this command to all ESCs on the CAN bus
*/
typedef struct
{
uint16_t rpmCommand; //!< RPM Command
}ESC_RPMCommand_t;
//! Create the ESC_RPMCommand packet from parameters
void encodeESC_RPMCommandPacket(void* pkt, uint16_t rpmCommand);
//! Decode the ESC_RPMCommand packet
//! Decode the ESC_RPMCommand packet to parameters
int decodeESC_RPMCommandPacket(const void* pkt, uint16_t* rpmCommand);
//! return the packet ID for the ESC_RPMCommand packet
@ -169,31 +210,23 @@ int decodeESC_RPMCommandPacket(const void* pkt, uint16_t* rpmCommand);
/*!
* The ESC_STATUS_A packet contains high-priority ESC status information. This
* packet is transmitted by the ESC at regular (user-configurable) intervals. It
* can also be requested (polled) from the ESC by sending a zero-length packet
* of the same type.
* packet is transmitted by the ESC at regular (user-configurable) intervals.
* It can also be requested (polled) from the ESC by sending a zero-length
* packet of the same type.
*/
typedef struct
{
uint8_t mode; //!< ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use.
ESC_StatusBits_t status; //!< ESC status bits
ESC_WarningBits_t warnings; //!< ESC warning bits
ESC_ErrorBits_t errors; //!< ESC *error* bits
uint16_t command; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
uint8_t mode; //!< ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper three bits are used for debugging and should be ignored for general use.
ESC_StatusBits_t status; //!< ESC status bits
uint16_t command; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
}ESC_StatusA_t;
//! Create the ESC_StatusA packet
void encodeESC_StatusAPacketStructure(void* pkt, const ESC_StatusA_t* user);
//! Create the ESC_StatusA packet from parameters
void encodeESC_StatusAPacket(void* pkt, uint8_t mode, const ESC_StatusBits_t* status, uint16_t command, uint16_t rpm);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacketStructure(const void* pkt, ESC_StatusA_t* user);
//! Create the ESC_StatusA packet
void encodeESC_StatusAPacket(void* pkt, uint8_t mode, const ESC_StatusBits_t* status, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors, uint16_t command, uint16_t rpm);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacket(const void* pkt, uint8_t* mode, ESC_StatusBits_t* status, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors, uint16_t* command, uint16_t* rpm);
//! Decode the ESC_StatusA packet to parameters
int decodeESC_StatusAPacket(const void* pkt, uint8_t* mode, ESC_StatusBits_t* status, uint16_t* command, uint16_t* rpm);
//! return the packet ID for the ESC_StatusA packet
#define getESC_StatusAPacketID() (PKT_ESC_STATUS_A)
@ -215,20 +248,14 @@ typedef struct
uint16_t voltage; //!< ESC Rail Voltage
int16_t current; //!< ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
uint16_t dutyCycle; //!< ESC Motor Duty Cycle
int8_t escTemperature; //!< ESC Board Temperature
int8_t escTemperature; //!< ESC Logic Board Temperature
uint8_t motorTemperature; //!< ESC Motor Temperature
}ESC_StatusB_t;
//! Create the ESC_StatusB packet
void encodeESC_StatusBPacketStructure(void* pkt, const ESC_StatusB_t* user);
//! Decode the ESC_StatusB packet
int decodeESC_StatusBPacketStructure(const void* pkt, ESC_StatusB_t* user);
//! Create the ESC_StatusB packet
//! Create the ESC_StatusB packet from parameters
void encodeESC_StatusBPacket(void* pkt, uint16_t voltage, int16_t current, uint16_t dutyCycle, int8_t escTemperature, uint8_t motorTemperature);
//! Decode the ESC_StatusB packet
//! Decode the ESC_StatusB packet to parameters
int decodeESC_StatusBPacket(const void* pkt, uint16_t* voltage, int16_t* current, uint16_t* dutyCycle, int8_t* escTemperature, uint8_t* motorTemperature);
//! return the packet ID for the ESC_StatusB packet
@ -241,10 +268,36 @@ int decodeESC_StatusBPacket(const void* pkt, uint16_t* voltage, int16_t* current
#define getESC_StatusBMaxDataLength() (8)
/*!
* This packet contains raw accelerometer data from the ESC. It can be requested
* (polled) from the ESC by sending a zero-length packet of the same type. It
* can also be transmitted by the ESC at high-frequency using the high-frequency
* streaming functionality of the ESC
* ESC Status C telemetry packet transmitted by the ESC at regular intervals
* (reserved for future use)
*/
typedef struct
{
float fetTemperature; //!< ESC Phase Board Temperature
uint16_t pwmFrequency; //!< Current motor PWM frequency (10 Hz per bit)
uint16_t timingAdvance; //!< Current timing advance (0.1 degree per bit)
}ESC_StatusC_t;
//! Create the ESC_StatusC packet from parameters
void encodeESC_StatusCPacket(void* pkt, float fetTemperature, uint16_t pwmFrequency, uint16_t timingAdvance);
//! Decode the ESC_StatusC packet to parameters
int decodeESC_StatusCPacket(const void* pkt, float* fetTemperature, uint16_t* pwmFrequency, uint16_t* timingAdvance);
//! return the packet ID for the ESC_StatusC packet
#define getESC_StatusCPacketID() (PKT_ESC_STATUS_C)
//! return the minimum encoded length for the ESC_StatusC packet
#define getESC_StatusCMinDataLength() (7)
//! return the maximum encoded length for the ESC_StatusC packet
#define getESC_StatusCMaxDataLength() (7)
/*!
* This packet contains raw accelerometer data from the ESC. It can be
* requested (polled) from the ESC by sending a zero-length packet of the same
* type. It can also be transmitted by the ESC at high-frequency using the
* high-frequency streaming functionality of the ESC
*/
typedef struct
{
@ -255,16 +308,10 @@ typedef struct
uint8_t resolution; //!< Accelerometer measurement resolution, in 'bits'.
}ESC_Accelerometer_t;
//! Create the ESC_Accelerometer packet
void encodeESC_AccelerometerPacketStructure(void* pkt, const ESC_Accelerometer_t* user);
//! Decode the ESC_Accelerometer packet
int decodeESC_AccelerometerPacketStructure(const void* pkt, ESC_Accelerometer_t* user);
//! Create the ESC_Accelerometer packet
//! Create the ESC_Accelerometer packet from parameters
void encodeESC_AccelerometerPacket(void* pkt, int16_t xAcc, int16_t yAcc, int16_t zAcc, uint8_t fullscale, uint8_t resolution);
//! Decode the ESC_Accelerometer packet
//! Decode the ESC_Accelerometer packet to parameters
int decodeESC_AccelerometerPacket(const void* pkt, int16_t* xAcc, int16_t* yAcc, int16_t* zAcc, uint8_t* fullscale, uint8_t* resolution);
//! return the packet ID for the ESC_Accelerometer packet
@ -276,6 +323,68 @@ int decodeESC_AccelerometerPacket(const void* pkt, int16_t* xAcc, int16_t* yAcc,
//! return the maximum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMaxDataLength() (8)
/*!
* Warning and error status information
*/
typedef struct
{
ESC_WarningBits_t warnings;
ESC_ErrorBits_t errors;
}ESC_WarningErrorStatus_t;
//! Create the ESC_WarningErrorStatus packet
void encodeESC_WarningErrorStatusPacketStructure(void* pkt, const ESC_WarningErrorStatus_t* user);
//! Decode the ESC_WarningErrorStatus packet
int decodeESC_WarningErrorStatusPacketStructure(const void* pkt, ESC_WarningErrorStatus_t* user);
//! Create the ESC_WarningErrorStatus packet from parameters
void encodeESC_WarningErrorStatusPacket(void* pkt, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors);
//! Decode the ESC_WarningErrorStatus packet to parameters
int decodeESC_WarningErrorStatusPacket(const void* pkt, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors);
//! return the packet ID for the ESC_WarningErrorStatus packet
#define getESC_WarningErrorStatusPacketID() (PKT_ESC_WARNINGS_ERRORS)
//! return the minimum encoded length for the ESC_WarningErrorStatus packet
#define getESC_WarningErrorStatusMinDataLength() (4)
//! return the maximum encoded length for the ESC_WarningErrorStatus packet
#define getESC_WarningErrorStatusMaxDataLength() (4)
/*!
* Motor status flags
*/
typedef struct
{
uint16_t standbyCause; //!< Cause of most recent standby event
uint16_t disableCause; //!< Cause of most recent disable event
uint16_t offCause; //!< Cause of most recent motor-stop event
uint16_t failedStartCause; //!< Cause of most recent failed-start
}ESC_MotorStatusFlags_t;
//! Create the ESC_MotorStatusFlags packet
void encodeESC_MotorStatusFlagsPacketStructure(void* pkt, const ESC_MotorStatusFlags_t* user);
//! Decode the ESC_MotorStatusFlags packet
int decodeESC_MotorStatusFlagsPacketStructure(const void* pkt, ESC_MotorStatusFlags_t* user);
//! Create the ESC_MotorStatusFlags packet from parameters
void encodeESC_MotorStatusFlagsPacket(void* pkt, uint16_t standbyCause, uint16_t disableCause, uint16_t offCause, uint16_t failedStartCause);
//! Decode the ESC_MotorStatusFlags packet to parameters
int decodeESC_MotorStatusFlagsPacket(const void* pkt, uint16_t* standbyCause, uint16_t* disableCause, uint16_t* offCause, uint16_t* failedStartCause);
//! return the packet ID for the ESC_MotorStatusFlags packet
#define getESC_MotorStatusFlagsPacketID() (PKT_ESC_MOTOR_FLAGS)
//! return the minimum encoded length for the ESC_MotorStatusFlags packet
#define getESC_MotorStatusFlagsMinDataLength() (8)
//! return the maximum encoded length for the ESC_MotorStatusFlags packet
#define getESC_MotorStatusFlagsMaxDataLength() (8)
/*!
* This packet contains the serial number for the ESC. Additionally there are
* two extra values (each 16-bit) which can be programmed by the user for any
@ -283,8 +392,9 @@ int decodeESC_AccelerometerPacket(const void* pkt, int16_t* xAcc, int16_t* yAcc,
*/
typedef struct
{
uint8_t HardwareRevision; //!< ESC hardware revision
uint32_t SerialNumber; //!< ESC Serial Number (OTP - not configurable by user)
uint8_t HardwareRevision; //!< ESC hardware revision (OTP - not configurable by user)
uint8_t Model; //!< ESC model (OTP - not configurable by user)
uint16_t SerialNumber; //!< ESC Serial Number (OTP - not configurable by user)
uint16_t UserIDA; //!< User ID Value A - user can set this value to any value
uint16_t UserIDB; //!< User ID Value B - user can set this value to any value
}ESC_Address_t;
@ -295,11 +405,11 @@ void encodeESC_AddressPacketStructure(void* pkt, const ESC_Address_t* user);
//! Decode the ESC_Address packet
int decodeESC_AddressPacketStructure(const void* pkt, ESC_Address_t* user);
//! Create the ESC_Address packet
void encodeESC_AddressPacket(void* pkt, uint8_t HardwareRevision, uint32_t SerialNumber, uint16_t UserIDA, uint16_t UserIDB);
//! Create the ESC_Address packet from parameters
void encodeESC_AddressPacket(void* pkt, uint8_t HardwareRevision, uint8_t Model, uint16_t SerialNumber, uint16_t UserIDA, uint16_t UserIDB);
//! Decode the ESC_Address packet
int decodeESC_AddressPacket(const void* pkt, uint8_t* HardwareRevision, uint32_t* SerialNumber, uint16_t* UserIDA, uint16_t* UserIDB);
//! Decode the ESC_Address packet to parameters
int decodeESC_AddressPacket(const void* pkt, uint8_t* HardwareRevision, uint8_t* Model, uint16_t* SerialNumber, uint16_t* UserIDA, uint16_t* UserIDB);
//! return the packet ID for the ESC_Address packet
#define getESC_AddressPacketID() (PKT_ESC_SERIAL_NUMBER)
@ -310,10 +420,19 @@ int decodeESC_AddressPacket(const void* pkt, uint8_t* HardwareRevision, uint32_t
//! return the maximum encoded length for the ESC_Address packet
#define getESC_AddressMaxDataLength() (8)
//! Create the ESC_Title packet
/*!
* This packet contains a zero-terminated string (max-length 8) used to
* identify the particular ESC.
*/
typedef struct
{
uint8_t ESCTitle[8]; //!< Description of this ESC
}ESC_Title_t;
//! Create the ESC_Title packet from parameters
void encodeESC_TitlePacket(void* pkt, const uint8_t ESCTitle[8]);
//! Decode the ESC_Title packet
//! Decode the ESC_Title packet to parameters
int decodeESC_TitlePacket(const void* pkt, uint8_t ESCTitle[8]);
//! return the packet ID for the ESC_Title packet
@ -344,10 +463,10 @@ void encodeESC_FirmwarePacketStructure(void* pkt, const ESC_Firmware_t* user);
//! Decode the ESC_Firmware packet
int decodeESC_FirmwarePacketStructure(const void* pkt, ESC_Firmware_t* user);
//! Create the ESC_Firmware packet
//! Create the ESC_Firmware packet from parameters
void encodeESC_FirmwarePacket(void* pkt, uint8_t versionMajor, uint8_t versionMinor, uint8_t versionDay, uint8_t versionMonth, uint16_t versionYear, uint16_t firmwareChecksum);
//! Decode the ESC_Firmware packet
//! Decode the ESC_Firmware packet to parameters
int decodeESC_FirmwarePacket(const void* pkt, uint8_t* versionMajor, uint8_t* versionMinor, uint8_t* versionDay, uint8_t* versionMonth, uint16_t* versionYear, uint16_t* firmwareChecksum);
//! return the packet ID for the ESC_Firmware packet
@ -376,10 +495,10 @@ void encodeESC_SystemInfoPacketStructure(void* pkt, const ESC_SystemInfo_t* user
//! Decode the ESC_SystemInfo packet
int decodeESC_SystemInfoPacketStructure(const void* pkt, ESC_SystemInfo_t* user);
//! Create the ESC_SystemInfo packet
//! Create the ESC_SystemInfo packet from parameters
void encodeESC_SystemInfoPacket(void* pkt, uint32_t millisecondsSinceReset, uint16_t powerCycles, uint8_t resetCode, uint8_t cpuOccupancy);
//! Decode the ESC_SystemInfo packet
//! Decode the ESC_SystemInfo packet to parameters
int decodeESC_SystemInfoPacket(const void* pkt, uint32_t* millisecondsSinceReset, uint16_t* powerCycles, uint8_t* resetCode, uint8_t* cpuOccupancy);
//! return the packet ID for the ESC_SystemInfo packet
@ -400,16 +519,10 @@ typedef struct
char apiVersion[5]; //!< The API version of the ESC. Field is encoded constant.
}ESC_TelemetrySettings_t;
//! Set a ESC_TelemetrySettings_t structure to initial values
void initESC_TelemetrySettings_t(ESC_TelemetrySettings_t* user);
//! Verify a ESC_TelemetrySettings_t structure has acceptable values
int verifyESC_TelemetrySettings_t(ESC_TelemetrySettings_t* user);
//! Create the ESC_TelemetrySettings packet
//! Create the ESC_TelemetrySettings packet from parameters
void encodeESC_TelemetrySettingsPacket(void* pkt, const ESC_TelemetryConfig_t* settings);
//! Decode the ESC_TelemetrySettings packet
//! Decode the ESC_TelemetrySettings packet to parameters
int decodeESC_TelemetrySettingsPacket(const void* pkt, ESC_TelemetryConfig_t* settings, char apiVersion[5]);
//! return the packet ID for the ESC_TelemetrySettings packet
@ -426,9 +539,11 @@ int decodeESC_TelemetrySettingsPacket(const void* pkt, ESC_TelemetryConfig_t* se
*/
typedef struct
{
uint8_t version; //!< Version of EEPROM data
uint16_t size; //!< Size of settings data
uint16_t checksum; //!< Settings checksum
bool settingsLocked; //!< Set if the ESC settings are locked
uint8_t version; //!< Version of EEPROM data
uint16_t size; //!< Size of settings data
uint16_t checksum; //!< Settings checksum
uint16_t validatedChecksum; //!< Validated settings checksum
}ESC_EEPROMSettings_t;
//! Create the ESC_EEPROMSettings packet
@ -437,11 +552,11 @@ void encodeESC_EEPROMSettingsPacketStructure(void* pkt, const ESC_EEPROMSettings
//! Decode the ESC_EEPROMSettings packet
int decodeESC_EEPROMSettingsPacketStructure(const void* pkt, ESC_EEPROMSettings_t* user);
//! Create the ESC_EEPROMSettings packet
void encodeESC_EEPROMSettingsPacket(void* pkt, uint8_t version, uint16_t size, uint16_t checksum);
//! Create the ESC_EEPROMSettings packet from parameters
void encodeESC_EEPROMSettingsPacket(void* pkt, bool settingsLocked, uint8_t version, uint16_t size, uint16_t checksum, uint16_t validatedChecksum);
//! Decode the ESC_EEPROMSettings packet
int decodeESC_EEPROMSettingsPacket(const void* pkt, uint8_t* version, uint16_t* size, uint16_t* checksum);
//! Decode the ESC_EEPROMSettings packet to parameters
int decodeESC_EEPROMSettingsPacket(const void* pkt, bool* settingsLocked, uint8_t* version, uint16_t* size, uint16_t* checksum, uint16_t* validatedChecksum);
//! return the packet ID for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsPacketID() (PKT_ESC_EEPROM)
@ -450,9 +565,104 @@ int decodeESC_EEPROMSettingsPacket(const void* pkt, uint8_t* version, uint16_t*
#define getESC_EEPROMSettingsMinDataLength() (5)
//! return the maximum encoded length for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsMaxDataLength() (5)
#define getESC_EEPROMSettingsMaxDataLength() (7)
/*!
* ESC telltales
*/
typedef struct
{
uint8_t maxTemperature; //!< Maximum recorded internal temperature
uint8_t maxFetTemperature; //!< Maximum recorded MOSFET temperature
uint8_t maxMotorTemperature; //!< Maximum recorded motor temperature
uint8_t maxRippleVoltage; //!< Maximum recorded battery voltage
float maxBatteryCurrent; //!< Maximum recorded battery current
float maxRegenCurrent; //!< Maximum recorded regen current
uint16_t totalStarts; //!< Number of successful motor start events
uint16_t failedStarts; //!< Number of failed motor start events
uint32_t escRunTime; //!< ESC run time
uint32_t motorRunTime; //!< Motor run time
uint32_t desyncEvents; //!< Number of recorded motor desync events
}ESC_TelltaleValues_t;
//! Create the ESC_TelltaleValues packet
void encodeESC_TelltaleValuesPacketStructure(void* pkt, const ESC_TelltaleValues_t* user);
//! Decode the ESC_TelltaleValues packet
int decodeESC_TelltaleValuesPacketStructure(const void* pkt, ESC_TelltaleValues_t* user);
//! Create the ESC_TelltaleValues packet from parameters
void encodeESC_TelltaleValuesPacket(void* pkt, uint8_t maxTemperature, uint8_t maxFetTemperature, uint8_t maxMotorTemperature, uint8_t maxRippleVoltage, float maxBatteryCurrent, float maxRegenCurrent, uint16_t totalStarts, uint16_t failedStarts, uint32_t escRunTime, uint32_t motorRunTime, uint32_t desyncEvents);
//! Decode the ESC_TelltaleValues packet to parameters
int decodeESC_TelltaleValuesPacket(const void* pkt, uint8_t* maxTemperature, uint8_t* maxFetTemperature, uint8_t* maxMotorTemperature, uint8_t* maxRippleVoltage, float* maxBatteryCurrent, float* maxRegenCurrent, uint16_t* totalStarts, uint16_t* failedStarts, uint32_t* escRunTime, uint32_t* motorRunTime, uint32_t* desyncEvents);
//! return the packet ID for the ESC_TelltaleValues packet
#define getESC_TelltaleValuesPacketID() (PKT_ESC_TELLTALES)
//! return the minimum encoded length for the ESC_TelltaleValues packet
#define getESC_TelltaleValuesMinDataLength() (3)
//! return the maximum encoded length for the ESC_TelltaleValues packet
#define getESC_TelltaleValuesMaxDataLength() (24)
/*!
* Git commit hash for the ESC firmware
*/
typedef struct
{
char hash[8]; //!< git commit hash
}ESC_GitHash_t;
//! Create the ESC_GitHash packet from parameters
void encodeESC_GitHashPacket(void* pkt, const char hash[8]);
//! Decode the ESC_GitHash packet to parameters
int decodeESC_GitHashPacket(const void* pkt, char hash[8]);
//! return the packet ID for the ESC_GitHash packet
#define getESC_GitHashPacketID() (PKT_ESC_GIT_HASH)
//! return the minimum encoded length for the ESC_GitHash packet
#define getESC_GitHashMinDataLength() (1)
//! return the maximum encoded length for the ESC_GitHash packet
#define getESC_GitHashMaxDataLength() (8)
/*!
* PWM input calibration
*/
typedef struct
{
uint8_t protocol; //!< Protocol version (reserved for future use). Field is encoded constant.
int8_t pwmOffset; //!< PWM offset compensation value
uint16_t inputMin; //!< PWM value corresponding with 0% throttle
uint16_t inputMax; //!< PWM value corresponding with 1000% throttle
uint16_t armThreshold; //!< PWM arming threshold
}ESC_PWMInputCalibration_t;
//! Create the ESC_PWMInputCalibration packet
void encodeESC_PWMInputCalibrationPacketStructure(void* pkt, const ESC_PWMInputCalibration_t* user);
//! Decode the ESC_PWMInputCalibration packet
int decodeESC_PWMInputCalibrationPacketStructure(const void* pkt, ESC_PWMInputCalibration_t* user);
//! Create the ESC_PWMInputCalibration packet from parameters
void encodeESC_PWMInputCalibrationPacket(void* pkt, int8_t pwmOffset, uint16_t inputMin, uint16_t inputMax, uint16_t armThreshold);
//! Decode the ESC_PWMInputCalibration packet to parameters
int decodeESC_PWMInputCalibrationPacket(const void* pkt, uint8_t* protocol, int8_t* pwmOffset, uint16_t* inputMin, uint16_t* inputMax, uint16_t* armThreshold);
//! return the packet ID for the ESC_PWMInputCalibration packet
#define getESC_PWMInputCalibrationPacketID() (PKT_ESC_PWM_INPUT_CALIBRATION)
//! return the minimum encoded length for the ESC_PWMInputCalibration packet
#define getESC_PWMInputCalibrationMinDataLength() (8)
//! return the maximum encoded length for the ESC_PWMInputCalibration packet
#define getESC_PWMInputCalibrationMaxDataLength() (8)
#ifdef __cplusplus
}
#endif
#endif
#endif // _ESCPACKETS_H

View File

@ -1,18 +1,9 @@
// ESCVelocityProtocol.c was generated by ProtoGen version 2.18.c
// ESCVelocityProtocol.c was generated by ProtoGen version 3.2.a
/*
This program 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 program 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/>.
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
@ -31,13 +22,13 @@ const char* ESCOperatingModes_EnumLabel(int value)
default:
return "";
case ESC_MODE_STANDBY:
return "ESC_MODE_STANDBY";
return translateESCVelocity("ESC_MODE_STANDBY");
case ESC_MODE_PWM:
return "ESC_MODE_PWM";
return translateESCVelocity("ESC_MODE_PWM");
case ESC_MODE_RPM:
return "ESC_MODE_RPM";
return translateESCVelocity("ESC_MODE_RPM");
case ESC_VALID_MODES:
return "ESC_VALID_MODES";
return translateESCVelocity("ESC_VALID_MODES");
}
}
@ -55,11 +46,11 @@ const char* ESCCommandSources_EnumLabel(int value)
default:
return "";
case ESC_COMMAND_SOURCE_NONE:
return "ESC_COMMAND_SOURCE_NONE";
return translateESCVelocity("ESC_COMMAND_SOURCE_NONE");
case ESC_COMMAND_SOURCE_CAN:
return "ESC_COMMAND_SOURCE_CAN";
return translateESCVelocity("ESC_COMMAND_SOURCE_CAN");
case ESC_COMMAND_SOURCE_PWM:
return "ESC_COMMAND_SOURCE_PWM";
return translateESCVelocity("ESC_COMMAND_SOURCE_PWM");
}
}
@ -77,11 +68,13 @@ const char* ESCMotorTemperatureSensor_EnumLabel(int value)
default:
return "";
case ESC_MOTOR_TEMP_SENSOR_OFF:
return "ESC_MOTOR_TEMP_SENSOR_OFF";
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_OFF");
case ESC_MOTOR_TEMP_SENSOR_KTY84:
return "ESC_MOTOR_TEMP_SENSOR_KTY84";
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_KTY84");
case ESC_MOTOR_TEMP_SENSOR_KTY83:
return "ESC_MOTOR_TEMP_SENSOR_KTY83";
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_KTY83");
case ESC_MOTOR_TEMP_SENSOR_CUSTOM:
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_CUSTOM");
}
}
@ -99,11 +92,309 @@ const char* ESCCommandPriorities_EnumLabel(int value)
default:
return "";
case ESC_COMMAND_PRIORITY_CAN_ONLY:
return "ESC_COMMAND_PRIORITY_CAN_ONLY";
return translateESCVelocity("ESC_COMMAND_PRIORITY_CAN_ONLY");
case ESC_COMMAND_PRIORITY_CAN_PRIORITY:
return "ESC_COMMAND_PRIORITY_CAN_PRIORITY";
return translateESCVelocity("ESC_COMMAND_PRIORITY_CAN_PRIORITY");
case ESC_COMMAND_PRIORITY_PWM_PRIORITY:
return "ESC_COMMAND_PRIORITY_PWM_PRIORITY";
return translateESCVelocity("ESC_COMMAND_PRIORITY_PWM_PRIORITY");
}
}
/*!
* \brief Lookup label for 'ESCMotorDirection' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCMotorDirection_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_MOTOR_DIR_ABC:
return translateESCVelocity("ESC_MOTOR_DIR_ABC");
case ESC_MOTOR_DIR_ACB:
return translateESCVelocity("ESC_MOTOR_DIR_ACB");
case ESC_MOTOR_DIR_OTHER:
return translateESCVelocity("ESC_MOTOR_DIR_OTHER");
}
}
/*!
* \brief Lookup label for 'ESCHallSensorMode' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCHallSensorMode_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_HALL_MODE_SENSORLESS:
return translateESCVelocity("ESC_HALL_MODE_SENSORLESS");
case ESC_HALL_MODE_SENSORED:
return translateESCVelocity("ESC_HALL_MODE_SENSORED");
case ESC_HALL_MODE_SENSORED_STARTING:
return translateESCVelocity("ESC_HALL_MODE_SENSORED_STARTING");
}
}
/*!
* \brief Lookup label for 'ESCAFWModes' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCAFWModes_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_AFW_MODE_OFF:
return translateESCVelocity("ESC_AFW_MODE_OFF");
case ESC_AFW_MODE_ON:
return translateESCVelocity("ESC_AFW_MODE_ON");
case ESC_AFW_MODE_DYNAMIC:
return translateESCVelocity("ESC_AFW_MODE_DYNAMIC");
case ESC_AFW_MODE_OTHER:
return translateESCVelocity("ESC_AFW_MODE_OTHER");
}
}
/*!
* \brief Lookup label for 'ESCPWMFreqModes' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCPWMFreqModes_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_PWM_FREQ_FIXED:
return translateESCVelocity("ESC_PWM_FREQ_FIXED");
case ESC_PWM_FREQ_RAMP:
return translateESCVelocity("ESC_PWM_FREQ_RAMP");
case ESC_PWM_FREQ_OTHER:
return translateESCVelocity("ESC_PWM_FREQ_OTHER");
}
}
/*!
* \brief Lookup label for 'ESCTimingAdvanceModes' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCTimingAdvanceModes_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_TIMING_ADVANCE_MODE_FIXED:
return translateESCVelocity("ESC_TIMING_ADVANCE_MODE_FIXED");
case ESC_TIMING_ADVANCE_MODE_RAMP:
return translateESCVelocity("ESC_TIMING_ADVANCE_MODE_RAMP");
case ESC_TIMING_ADVANCE_MODE_OTHER:
return translateESCVelocity("ESC_TIMING_ADVANCE_MODE_OTHER");
}
}
/*!
* \brief Lookup label for 'ESCProtectionActions' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCProtectionActions_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_PROTECTION_WARNING:
return translateESCVelocity("ESC_PROTECTION_WARNING");
case ESC_PROTECTION_FOLDBACK:
return translateESCVelocity("ESC_PROTECTION_FOLDBACK");
case ESC_PROTECTION_DISABLE:
return translateESCVelocity("ESC_PROTECTION_DISABLE");
case ESC_PROTECTION_INVALID:
return translateESCVelocity("ESC_PROTECTION_INVALID");
}
}
/*!
* \brief Lookup label for 'ESCBeepModes' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCBeepModes_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_BEEP_NONE:
return translateESCVelocity("ESC_BEEP_NONE");
case ESC_BEEP_STATUS:
return translateESCVelocity("ESC_BEEP_STATUS");
case ESC_BEEP_ERROR:
return translateESCVelocity("ESC_BEEP_ERROR");
case ESC_BEEP_ALL:
return translateESCVelocity("ESC_BEEP_ALL");
}
}
/*!
* \brief Lookup label for 'ESCStandbyCause' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCStandbyCause_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_STANDBY_CAUSE_CMD:
return translateESCVelocity("ESC_STANDBY_CAUSE_CMD");
case ESC_STANDBY_CAUSE_INHIBIT:
return translateESCVelocity("ESC_STANDBY_CAUSE_INHIBIT");
case ESC_STANDBY_CAUSE_TIMEOUT:
return translateESCVelocity("ESC_STANDBY_CAUSE_TIMEOUT");
case ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR:
return translateESCVelocity("ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR");
case ESC_STANDBY_CAUSE_INVALID_CMD:
return translateESCVelocity("ESC_STANDBY_CAUSE_INVALID_CMD");
case ESC_STANDBY_CAUSE_PWM_ARM:
return translateESCVelocity("ESC_STANDBY_CAUSE_PWM_ARM");
case ESC_STANDBY_CAUSE_FAILED_START:
return translateESCVelocity("ESC_STANDBY_CAUSE_FAILED_START");
case ESC_STANDBY_CAUSE_MIN_CMD:
return translateESCVelocity("ESC_STANDBY_CAUSE_MIN_CMD");
case ESC_STANDBY_CAUSE_FAILED_RESYNC:
return translateESCVelocity("ESC_STANDBY_CAUSE_FAILED_RESYNC");
case ESC_STANDBY_CAUSE_RESET:
return translateESCVelocity("ESC_STANDBY_CAUSE_RESET");
}
}
/*!
* \brief Lookup label for 'ESCDisableCause' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCDisableCause_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_DISABLE_CAUSE_NONE:
return translateESCVelocity("ESC_DISABLE_CAUSE_NONE");
case ESC_DISABLE_CAUSE_CAN_CMD:
return translateESCVelocity("ESC_DISABLE_CAUSE_CAN_CMD");
case ESC_DISABLE_CAUSE_PWM_TIMEOUT:
return translateESCVelocity("ESC_DISABLE_CAUSE_PWM_TIMEOUT");
case ESC_DISABLE_CAUSE_HARDWARE:
return translateESCVelocity("ESC_DISABLE_CAUSE_HARDWARE");
case ESC_DISABLE_CAUSE_OVERCURRENT:
return translateESCVelocity("ESC_DISABLE_CAUSE_OVERCURRENT");
case ESC_DISABLE_CAUSE_OVERSPEED:
return translateESCVelocity("ESC_DISABLE_CAUSE_OVERSPEED");
case ESC_DISABLE_CAUSE_OVERTEMP:
return translateESCVelocity("ESC_DISABLE_CAUSE_OVERTEMP");
case ESC_DISABLE_CAUSE_UNDERVOLTAGE:
return translateESCVelocity("ESC_DISABLE_CAUSE_UNDERVOLTAGE");
case ESC_DISABLE_CAUSE_FAILED_START:
return translateESCVelocity("ESC_DISABLE_CAUSE_FAILED_START");
case ESC_DISABLE_CAUSE_COMMUTATION_ERROR:
return translateESCVelocity("ESC_DISABLE_CAUSE_COMMUTATION_ERROR");
case ESC_DISABLE_CAUSE_INVALID_STATE:
return translateESCVelocity("ESC_DISABLE_CAUSE_INVALID_STATE");
case ESC_DISABLE_CAUSE_RESET:
return translateESCVelocity("ESC_DISABLE_CAUSE_RESET");
}
}
/*!
* \brief Lookup label for 'ESCMotorOffCause' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCMotorOffCause_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_MOTOR_OFF_STANDBY:
return translateESCVelocity("ESC_MOTOR_OFF_STANDBY");
case ESC_MOTOR_OFF_BEEP:
return translateESCVelocity("ESC_MOTOR_OFF_BEEP");
case ESC_MOTOR_OFF_INITIALISE:
return translateESCVelocity("ESC_MOTOR_OFF_INITIALISE");
case ESC_MOTOR_OFF_INHIBITED:
return translateESCVelocity("ESC_MOTOR_OFF_INHIBITED");
case ESC_MOTOR_OFF_THROTTLE_MIN:
return translateESCVelocity("ESC_MOTOR_OFF_THROTTLE_MIN");
case ESC_MOTOR_OFF_NOT_RUNNING:
return translateESCVelocity("ESC_MOTOR_OFF_NOT_RUNNING");
case ESC_MOTOR_OFF_FAILED_START:
return translateESCVelocity("ESC_MOTOR_OFF_FAILED_START");
case ESC_MOTOR_OFF_INVALID:
return translateESCVelocity("ESC_MOTOR_OFF_INVALID");
}
}
/*!
* \brief Lookup label for 'ESCFailedStartCause' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCFailedStartCause_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_FAILED_START_CAUSE_RESET:
return translateESCVelocity("ESC_FAILED_START_CAUSE_RESET");
case ESC_FAILED_START_CAUSE_TIMEOUT:
return translateESCVelocity("ESC_FAILED_START_CAUSE_TIMEOUT");
case ESC_FAILED_START_CAUSE_OVERSPEED:
return translateESCVelocity("ESC_FAILED_START_CAUSE_OVERSPEED");
case ESC_FAILED_START_CAUSE_OVERCURRENT:
return translateESCVelocity("ESC_FAILED_START_CAUSE_OVERCURRENT");
case ESC_FAILED_START_CAUSE_SPIN_REVERSED:
return translateESCVelocity("ESC_FAILED_START_CAUSE_SPIN_REVERSED");
case ESC_FAILED_START_CAUSE_SPIN_TOO_FAST:
return translateESCVelocity("ESC_FAILED_START_CAUSE_SPIN_TOO_FAST");
case ESC_FAILED_START_CAUSE_INVALID:
return translateESCVelocity("ESC_FAILED_START_CAUSE_INVALID");
}
}
@ -121,37 +412,37 @@ const char* ESCMultiCommandPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_SETPOINT_1:
return "PKT_ESC_SETPOINT_1";
return translateESCVelocity("PKT_ESC_SETPOINT_1");
case PKT_ESC_SETPOINT_2:
return "PKT_ESC_SETPOINT_2";
return translateESCVelocity("PKT_ESC_SETPOINT_2");
case PKT_ESC_SETPOINT_3:
return "PKT_ESC_SETPOINT_3";
return translateESCVelocity("PKT_ESC_SETPOINT_3");
case PKT_ESC_SETPOINT_4:
return "PKT_ESC_SETPOINT_4";
return translateESCVelocity("PKT_ESC_SETPOINT_4");
case PKT_ESC_SETPOINT_5:
return "PKT_ESC_SETPOINT_5";
return translateESCVelocity("PKT_ESC_SETPOINT_5");
case PKT_ESC_SETPOINT_6:
return "PKT_ESC_SETPOINT_6";
return translateESCVelocity("PKT_ESC_SETPOINT_6");
case PKT_ESC_SETPOINT_7:
return "PKT_ESC_SETPOINT_7";
return translateESCVelocity("PKT_ESC_SETPOINT_7");
case PKT_ESC_SETPOINT_8:
return "PKT_ESC_SETPOINT_8";
return translateESCVelocity("PKT_ESC_SETPOINT_8");
case PKT_ESC_SETPOINT_9:
return "PKT_ESC_SETPOINT_9";
return translateESCVelocity("PKT_ESC_SETPOINT_9");
case PKT_ESC_SETPOINT_10:
return "PKT_ESC_SETPOINT_10";
return translateESCVelocity("PKT_ESC_SETPOINT_10");
case PKT_ESC_SETPOINT_11:
return "PKT_ESC_SETPOINT_11";
return translateESCVelocity("PKT_ESC_SETPOINT_11");
case PKT_ESC_SETPOINT_12:
return "PKT_ESC_SETPOINT_12";
return translateESCVelocity("PKT_ESC_SETPOINT_12");
case PKT_ESC_SETPOINT_13:
return "PKT_ESC_SETPOINT_13";
return translateESCVelocity("PKT_ESC_SETPOINT_13");
case PKT_ESC_SETPOINT_14:
return "PKT_ESC_SETPOINT_14";
return translateESCVelocity("PKT_ESC_SETPOINT_14");
case PKT_ESC_SETPOINT_15:
return "PKT_ESC_SETPOINT_15";
return translateESCVelocity("PKT_ESC_SETPOINT_15");
case PKT_ESC_SETPOINT_16:
return "PKT_ESC_SETPOINT_16";
return translateESCVelocity("PKT_ESC_SETPOINT_16");
}
}
@ -169,13 +460,13 @@ const char* ESCCommandPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_PWM_CMD:
return "PKT_ESC_PWM_CMD";
return translateESCVelocity("PKT_ESC_PWM_CMD");
case PKT_ESC_RPM_CMD:
return "PKT_ESC_RPM_CMD";
return translateESCVelocity("PKT_ESC_RPM_CMD");
case PKT_ESC_DISABLE:
return "PKT_ESC_DISABLE";
return translateESCVelocity("PKT_ESC_DISABLE");
case PKT_ESC_STANDBY:
return "PKT_ESC_STANDBY";
return translateESCVelocity("PKT_ESC_STANDBY");
}
}
@ -193,11 +484,15 @@ const char* ESCStatusPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_STATUS_A:
return "PKT_ESC_STATUS_A";
return translateESCVelocity("PKT_ESC_STATUS_A");
case PKT_ESC_STATUS_B:
return "PKT_ESC_STATUS_B";
return translateESCVelocity("PKT_ESC_STATUS_B");
case PKT_ESC_STATUS_C:
return translateESCVelocity("PKT_ESC_STATUS_C");
case PKT_ESC_STATUS_D:
return translateESCVelocity("PKT_ESC_STATUS_D");
case PKT_ESC_ACCELEROMETER:
return "PKT_ESC_ACCELEROMETER";
return translateESCVelocity("PKT_ESC_ACCELEROMETER");
}
}
@ -214,18 +509,126 @@ const char* ESCPackets_EnumLabel(int value)
{
default:
return "";
case PKT_ESC_SYSTEM_CMD:
return translateESCVelocity("PKT_ESC_SYSTEM_CMD");
case PKT_ESC_SET_TITLE:
return translateESCVelocity("PKT_ESC_SET_TITLE");
case PKT_ESC_CONTROL_LOOP_DATA:
return translateESCVelocity("PKT_ESC_CONTROL_LOOP_DATA");
case PKT_ESC_WARNINGS_ERRORS:
return translateESCVelocity("PKT_ESC_WARNINGS_ERRORS");
case PKT_ESC_MOTOR_FLAGS:
return translateESCVelocity("PKT_ESC_MOTOR_FLAGS");
case PKT_ESC_EVENT:
return translateESCVelocity("PKT_ESC_EVENT");
case PKT_ESC_SERIAL_NUMBER:
return "PKT_ESC_SERIAL_NUMBER";
return translateESCVelocity("PKT_ESC_SERIAL_NUMBER");
case PKT_ESC_TITLE:
return "PKT_ESC_TITLE";
return translateESCVelocity("PKT_ESC_TITLE");
case PKT_ESC_FIRMWARE:
return "PKT_ESC_FIRMWARE";
return translateESCVelocity("PKT_ESC_FIRMWARE");
case PKT_ESC_SYSTEM_INFO:
return "PKT_ESC_SYSTEM_INFO";
return translateESCVelocity("PKT_ESC_SYSTEM_INFO");
case PKT_ESC_TELEMETRY_SETTINGS:
return "PKT_ESC_TELEMETRY_SETTINGS";
return translateESCVelocity("PKT_ESC_TELEMETRY_SETTINGS");
case PKT_ESC_EEPROM:
return "PKT_ESC_EEPROM";
return translateESCVelocity("PKT_ESC_EEPROM");
case PKT_ESC_EXTRA:
return translateESCVelocity("PKT_ESC_EXTRA");
case PKT_ESC_COMMISSIONING:
return translateESCVelocity("PKT_ESC_COMMISSIONING");
case PKT_ESC_TELLTALES:
return translateESCVelocity("PKT_ESC_TELLTALES");
case PKT_ESC_GIT_HASH:
return translateESCVelocity("PKT_ESC_GIT_HASH");
case PKT_ESC_LEGACY_MOTOR_STATUS:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_STATUS");
case PKT_ESC_LEGACY_MOTOR_SETTINGS:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_SETTINGS");
case PKT_ESC_LEGACY_MOTOR_SETTINGS_2:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_SETTINGS_2");
case PKT_ESC_LEGACY_MOTOR_FIRMWARE:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_FIRMWARE");
case PKT_ESC_MOTOR_SETTINGS:
return translateESCVelocity("PKT_ESC_MOTOR_SETTINGS");
case PKT_ESC_MOTOR_STARTING:
return translateESCVelocity("PKT_ESC_MOTOR_STARTING");
case PKT_ESC_MOTOR_PARAMETERS:
return translateESCVelocity("PKT_ESC_MOTOR_PARAMETERS");
case PKT_ESC_CONFIG:
return translateESCVelocity("PKT_ESC_CONFIG");
case PKT_ESC_WARNINGS:
return translateESCVelocity("PKT_ESC_WARNINGS");
case PKT_ESC_PROTECTION_LEVELS:
return translateESCVelocity("PKT_ESC_PROTECTION_LEVELS");
case PKT_ESC_PROTECTION_ACTIONS:
return translateESCVelocity("PKT_ESC_PROTECTION_ACTIONS");
case PKT_ESC_RPM_LOOP_SETTINGS:
return translateESCVelocity("PKT_ESC_RPM_LOOP_SETTINGS");
case PKT_ESC_STARTING_SETTINGS:
return translateESCVelocity("PKT_ESC_STARTING_SETTINGS");
case PKT_ESC_CURRENT_CALIBRATION:
return translateESCVelocity("PKT_ESC_CURRENT_CALIBRATION");
case PKT_ESC_IO_TABLE_SETTINGS:
return translateESCVelocity("PKT_ESC_IO_TABLE_SETTINGS");
case PKT_ESC_IO_TABLE_ELEMENT:
return translateESCVelocity("PKT_ESC_IO_TABLE_ELEMENT");
case PKT_ESC_THROTTLE_CURVE:
return translateESCVelocity("PKT_ESC_THROTTLE_CURVE");
case PKT_ESC_PWM_INPUT_CALIBRATION:
return translateESCVelocity("PKT_ESC_PWM_INPUT_CALIBRATION");
case PKT_ESC_BULK_TRANSFER:
return translateESCVelocity("PKT_ESC_BULK_TRANSFER");
}
}
/*!
* \brief Lookup label for 'ESCSystemCommands' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCSystemCommands_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case CMD_ESC_SET_NODE_ID:
return translateESCVelocity("CMD_ESC_SET_NODE_ID");
case CMD_ESC_SET_USER_ID_A:
return translateESCVelocity("CMD_ESC_SET_USER_ID_A");
case CMD_ESC_SET_USER_ID_B:
return translateESCVelocity("CMD_ESC_SET_USER_ID_B");
case CMD_ESC_TARE_CURRENT:
return translateESCVelocity("CMD_ESC_TARE_CURRENT");
case CMD_ESC_IDENTIFY:
return translateESCVelocity("CMD_ESC_IDENTIFY");
case CMD_ESC_REQUEST_HF_DATA:
return translateESCVelocity("CMD_ESC_REQUEST_HF_DATA");
case CMD_ESC_CONFIGURE_IO_MAP:
return translateESCVelocity("CMD_ESC_CONFIGURE_IO_MAP");
case CMD_ESC_CONFIGURE_IO_ELEMENT:
return translateESCVelocity("CMD_ESC_CONFIGURE_IO_ELEMENT");
case CMD_ESC_RESET_SETTINGS:
return translateESCVelocity("CMD_ESC_RESET_SETTINGS");
case CMD_ESC_ENTER_DEBUG:
return translateESCVelocity("CMD_ESC_ENTER_DEBUG");
case CMD_ESC_EXIT_DEBUG:
return translateESCVelocity("CMD_ESC_EXIT_DEBUG");
case CMD_ESC_UNLOCK_SETTINGS:
return translateESCVelocity("CMD_ESC_UNLOCK_SETTINGS");
case CMD_ESC_LOCK_SETTINGS:
return translateESCVelocity("CMD_ESC_LOCK_SETTINGS");
case CMD_ESC_VALIDATE_SETTINGS:
return translateESCVelocity("CMD_ESC_VALIDATE_SETTINGS");
case CMD_ESC_RESET_MOTOR_RUN_TIME:
return translateESCVelocity("CMD_ESC_RESET_MOTOR_RUN_TIME");
case CMD_ESC_ENTER_BOOTLOADER:
return translateESCVelocity("CMD_ESC_ENTER_BOOTLOADER");
case CMD_ESC_RESET:
return translateESCVelocity("CMD_ESC_RESET");
}
}

View File

@ -1,25 +1,16 @@
// ESCVelocityProtocol.h was generated by ProtoGen version 2.18.c
// ESCVelocityProtocol.h was generated by ProtoGen version 3.2.a
/*
This program 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 program 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/>.
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _ESCVELOCITYPROTOCOL_H
#define _ESCVELOCITYPROTOCOL_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
@ -27,29 +18,37 @@ extern "C" {
/*!
* \file
* \mainpage ESCVelocity protocol stack
*
* This is the ICD for the Currawong Engineering Electronic Speed Controller
* (ESCVelocity). This document details the ESCVelocity command and packet
* structure for communication with and configuration of the ESC
*
*
* This is the ICD for the Gen-2 Currawong Engineering Electronic Speed
* Controller (ESCVelocity). This document details the ESCVelocity command and
* packet structure for communication with and configuration of the ESC. Note
* that there may be some differences between this ICD and the ICD for the
* Gen-1 ESCVelocity. Please refer to the old ICD for the Gen-1 device.
*
* 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: 23
*
* The protocol version is 3.05
* The protocol enumeration for this version is: 62
*
* The protocol version is 3.41
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h> // C string manipulation function header
//! \return the protocol API enumeration
#define getESCVelocityApi() 23
#define getESCVelocityApi() 62
//! \return the protocol version string
#define getESCVelocityVersion() "3.05"
#define getESCVelocityVersion() "3.41"
// Translation provided externally. The macro takes a `const char *` and returns a `const char *`
#ifndef translateESCVelocity
#define translateESCVelocity(x) x
#endif
/*!
* ESC_Disable_Sequence
* Constant values required for sending a disable (inhibit) command
*/
typedef enum
{
@ -58,7 +57,7 @@ typedef enum
} ESCDisableSequence;
/*!
* ESC_Enable_Sequence
* Constant values required for sending an enable command
*/
typedef enum
{
@ -99,8 +98,9 @@ const char* ESCCommandSources_EnumLabel(int value);
typedef enum
{
ESC_MOTOR_TEMP_SENSOR_OFF = 0x00,//!< No temperature sensor selected
ESC_MOTOR_TEMP_SENSOR_KTY84, //!< KTY84 of equivalent
ESC_MOTOR_TEMP_SENSOR_KTY83 //!< KTY83 or equivalent
ESC_MOTOR_TEMP_SENSOR_KTY84, //!< KTY84 or equivalent
ESC_MOTOR_TEMP_SENSOR_KTY83, //!< KTY83 or equivalent
ESC_MOTOR_TEMP_SENSOR_CUSTOM //!< Use a custom temperature lookup table
} ESCMotorTemperatureSensor;
//! \return the label of a 'ESCMotorTemperatureSensor' enum entry, based on its value
@ -120,13 +120,84 @@ typedef enum
const char* ESCCommandPriorities_EnumLabel(int value);
/*!
* Motor Direction Enumeration
* Motor direction
*/
typedef enum
{
ESC_MOTOR_DIR_FORWARD = 0x00,//!< Forward motor direction
ESC_MOTOR_DIR_REVERSE = 0x01 //!< Reverse motor direction
} ESCMotorDirections;
ESC_MOTOR_DIR_ABC = 0, //!< Motor phase sequence A / B / C
ESC_MOTOR_DIR_ACB = 1, //!< Motor phase sequence A / C / B
ESC_MOTOR_DIR_OTHER = 3 //!< Unknown / unsupported direction
} ESCMotorDirection;
//! \return the label of a 'ESCMotorDirection' enum entry, based on its value
const char* ESCMotorDirection_EnumLabel(int value);
/*!
* Hall sensor modes
*/
typedef enum
{
ESC_HALL_MODE_SENSORLESS = 0, //!< Sensorless control only
ESC_HALL_MODE_SENSORED = 1, //!< Sensored control only
ESC_HALL_MODE_SENSORED_STARTING = 2 //!< Sensored starting transitioning to sensorless running
} ESCHallSensorMode;
//! \return the label of a 'ESCHallSensorMode' enum entry, based on its value
const char* ESCHallSensorMode_EnumLabel(int value);
/*!
* AFW operation modes
*/
typedef enum
{
ESC_AFW_MODE_OFF = 0, //!< AFW always off (during this motor running state)
ESC_AFW_MODE_ON = 1, //!< AFW always on (during this motor running state)
ESC_AFW_MODE_DYNAMIC = 2,//!< AFW may change state
ESC_AFW_MODE_OTHER = 3 //!< Future expansion
} ESCAFWModes;
//! \return the label of a 'ESCAFWModes' enum entry, based on its value
const char* ESCAFWModes_EnumLabel(int value);
/*!
* PWM operation modes
*/
typedef enum
{
ESC_PWM_FREQ_FIXED = 0,//!< PWM frequency is the specified value
ESC_PWM_FREQ_RAMP = 1,
ESC_PWM_FREQ_OTHER = 3 //!< Future expansion
} ESCPWMFreqModes;
//! \return the label of a 'ESCPWMFreqModes' enum entry, based on its value
const char* ESCPWMFreqModes_EnumLabel(int value);
/*!
* PWM operation modes
*/
typedef enum
{
ESC_TIMING_ADVANCE_MODE_FIXED = 0,//!< Timing advance is the specified value
ESC_TIMING_ADVANCE_MODE_RAMP = 1,
ESC_TIMING_ADVANCE_MODE_OTHER = 3 //!< Future expansion
} ESCTimingAdvanceModes;
//! \return the label of a 'ESCTimingAdvanceModes' enum entry, based on its value
const char* ESCTimingAdvanceModes_EnumLabel(int value);
/*!
* ESC protection actions
*/
typedef enum
{
ESC_PROTECTION_WARNING = 0, //!< Warning bit is set
ESC_PROTECTION_FOLDBACK = 1, //!< Motor duty cycle is limited
ESC_PROTECTION_DISABLE = 2, //!< ESC is disabled
ESC_PROTECTION_INVALID = 7 //!< Invalid protection action
} ESCProtectionActions;
//! \return the label of a 'ESCProtectionActions' enum entry, based on its value
const char* ESCProtectionActions_EnumLabel(int value);
/*!
* Motor beep modes enumeration
@ -139,6 +210,86 @@ typedef enum
ESC_BEEP_ALL = 0b11 //!< All motor beeps
} ESCBeepModes;
//! \return the label of a 'ESCBeepModes' enum entry, based on its value
const char* ESCBeepModes_EnumLabel(int value);
/*!
* ESC standby cause flags
*/
typedef enum
{
ESC_STANDBY_CAUSE_CMD = 0x0001, //!< ESC was put into *STANDBY* mode by a command
ESC_STANDBY_CAUSE_INHIBIT = 0x0002, //!< ESC was put into *STANDBY* mode by SW or HW inhibit
ESC_STANDBY_CAUSE_TIMEOUT = 0x0004, //!< ESC was put into *STANDBY* mode due to keepalive timeout
ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR = 0x0008,//!< ESC was put into *STANDBY* mode due to a hall sensor error
ESC_STANDBY_CAUSE_INVALID_CMD = 0x0010, //!< ESC was put into *STANDBY* mode due to a command being invalid
ESC_STANDBY_CAUSE_PWM_ARM = 0x0020, //!< PWM arming signal detected
ESC_STANDBY_CAUSE_FAILED_START = 0x0040, //!< ESC was put into *STANDBY* mode due to failed starting routine
ESC_STANDBY_CAUSE_MIN_CMD = 0x0080, //!< ESC was put into *STANDBY* mode due to the received command below minimum threshold
ESC_STANDBY_CAUSE_FAILED_RESYNC = 0x0100, //!< ESC was put into *STANDBY* mode due to failed resync routine
ESC_STANDBY_CAUSE_RESET = 0x8000
} ESCStandbyCause;
//! \return the label of a 'ESCStandbyCause' enum entry, based on its value
const char* ESCStandbyCause_EnumLabel(int value);
/*!
* ESC disable cause flags
*/
typedef enum
{
ESC_DISABLE_CAUSE_NONE = 0x0000, //!< Unused / blank value
ESC_DISABLE_CAUSE_CAN_CMD = 0x0001, //!< ESC is disabled by a CAN command
ESC_DISABLE_CAUSE_PWM_TIMEOUT = 0x0002, //!< PWM signal lost
ESC_DISABLE_CAUSE_HARDWARE = 0x0004, //!< Hardware enable signal deasserted
ESC_DISABLE_CAUSE_OVERCURRENT = 0x0008, //!< ESC disabled due to overcurrent
ESC_DISABLE_CAUSE_OVERSPEED = 0x0010, //!< ESC disabled due to overspeed
ESC_DISABLE_CAUSE_OVERTEMP = 0x0020, //!< ESC disabled due to overtemperature
ESC_DISABLE_CAUSE_UNDERVOLTAGE = 0x0040, //!< ESC disabled due to undervoltage
ESC_DISABLE_CAUSE_FAILED_START = 0x0080, //!< ESC disabled due to starting failure (see ESCFailedStartCause for details)
ESC_DISABLE_CAUSE_COMMUTATION_ERROR = 0x0100,//!< ESC disabled due to commutation failure
ESC_DISABLE_CAUSE_INVALID_STATE = 0x2000, //!< ESC disabled due to invalid commutation state
ESC_DISABLE_CAUSE_RESET = 0x8000 //!< ESC is disabled by processor reset
} ESCDisableCause;
//! \return the label of a 'ESCDisableCause' enum entry, based on its value
const char* ESCDisableCause_EnumLabel(int value);
/*!
* ESC motor OFF cause
*/
typedef enum
{
ESC_MOTOR_OFF_STANDBY = 0x0001, //!< Motor turned off due to system standby
ESC_MOTOR_OFF_BEEP = 0x0002, //!< Motor turned off due to beeping routine
ESC_MOTOR_OFF_INITIALISE = 0x0004, //!< Motor turned off at system initialisation
ESC_MOTOR_OFF_INHIBITED = 0x0010, //!< Motor turned off due to ESC being inhibited
ESC_MOTOR_OFF_THROTTLE_MIN = 0x0020, //!< Throttle below minimum value
ESC_MOTOR_OFF_NOT_RUNNING = 0x0040, //!< Motor does not have valid commutation
ESC_MOTOR_OFF_FAILED_START = 0x0080, //!< Starting routine failed
ESC_MOTOR_OFF_INVALID = 0x8000
} ESCMotorOffCause;
//! \return the label of a 'ESCMotorOffCause' enum entry, based on its value
const char* ESCMotorOffCause_EnumLabel(int value);
/*!
* Failed start cause flags
*/
typedef enum
{
ESC_FAILED_START_CAUSE_RESET = 0x0000, //!< No failed start has been recorded
ESC_FAILED_START_CAUSE_TIMEOUT = 0x0001, //!< Starting procedure timed out
ESC_FAILED_START_CAUSE_OVERSPEED = 0x0002, //!< Commutation speed too high
ESC_FAILED_START_CAUSE_OVERCURRENT = 0x0004, //!< Starting current exceeded
ESC_FAILED_START_CAUSE_SPIN_REVERSED = 0x0010,//!< Motor is already spinning, in reverse direction
ESC_FAILED_START_CAUSE_SPIN_TOO_FAST = 0x0020,//!< Motor is already spinning, above maximum catch speed
ESC_FAILED_START_CAUSE_INVALID = 0x8000
} ESCFailedStartCause;
//! \return the label of a 'ESCFailedStartCause' enum entry, based on its value
const char* ESCFailedStartCause_EnumLabel(int value);
/*!
* ESC Multi Command Packets
*/
@ -186,6 +337,8 @@ typedef enum
{
PKT_ESC_STATUS_A = 0x80, //!< ESC Status A telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_B, //!< ESC Status B telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_C, //!< ESC Status C telemetry packet transmitted by the ESC at regular intervals (reserved for future use)
PKT_ESC_STATUS_D, //!< Currently used for debug only
PKT_ESC_ACCELEROMETER = 0x88 //!< Raw accelerometer data
} ESCStatusPackets;
@ -197,17 +350,73 @@ const char* ESCStatusPackets_EnumLabel(int value);
*/
typedef enum
{
PKT_ESC_SERIAL_NUMBER = 0x90,//!< ESC Serial Number and User ID information
PKT_ESC_TITLE, //!< Human-readable string descriptor (max 8 chars) of the particular ESC
PKT_ESC_FIRMWARE, //!< ESC Firmware information
PKT_ESC_SYSTEM_INFO, //!< ESC system information packet
PKT_ESC_TELEMETRY_SETTINGS, //!< Telemetry packet configuration
PKT_ESC_EEPROM //!< ESC non-volatile data information and settings
PKT_ESC_SYSTEM_CMD = 0x50, //!< Send a configuration command to the ESC (followed by optional command data bytes)
PKT_ESC_SET_TITLE, //!< Set the ESC descriptor title
PKT_ESC_CONTROL_LOOP_DATA = 0x8A, //!< Control loop output data - varies depending on the operational mode of the ESC
PKT_ESC_WARNINGS_ERRORS = 0x86, //!< ESC warning / error status information.
PKT_ESC_MOTOR_FLAGS, //!< Motor status flags
PKT_ESC_EVENT = 0x8D, //!< Event description packet
PKT_ESC_SERIAL_NUMBER = 0x90, //!< ESC Serial Number and User ID information
PKT_ESC_TITLE, //!< Human-readable string descriptor (max 8 chars) of the particular ESC
PKT_ESC_FIRMWARE, //!< ESC Firmware information
PKT_ESC_SYSTEM_INFO, //!< ESC system information packet
PKT_ESC_TELEMETRY_SETTINGS, //!< Telemetry packet configuration
PKT_ESC_EEPROM, //!< ESC non-volatile data information and settings
PKT_ESC_EXTRA, //!< Extra settings
PKT_ESC_COMMISSIONING = 0x99, //!< ESC commissioning data (factory only)
PKT_ESC_TELLTALES, //!< ESC telltales
PKT_ESC_GIT_HASH, //!< ESC firmware git hash
PKT_ESC_LEGACY_MOTOR_STATUS = 0xA0, //!< ESC motor status information
PKT_ESC_LEGACY_MOTOR_SETTINGS = 0xA5,//!< ESC motor configuration
PKT_ESC_LEGACY_MOTOR_SETTINGS_2 = 0xA6,//!< ESC Motor settings information
PKT_ESC_LEGACY_MOTOR_FIRMWARE = 0xAA,//!< ESC motor control firmware information
PKT_ESC_MOTOR_SETTINGS = 0xA7, //!< Motor control settings packet
PKT_ESC_MOTOR_STARTING = 0xA8, //!< Motor starting settings packet
PKT_ESC_MOTOR_PARAMETERS = 0xA9, //!< Motor and system parameters
PKT_ESC_CONFIG = 0xB0, //!< ESC Configuration parameters
PKT_ESC_WARNINGS = 0xB1, //!< Warning level values for various ESC parameters (legacy)
PKT_ESC_PROTECTION_LEVELS = 0xB2, //!< ESC protection values
PKT_ESC_PROTECTION_ACTIONS = 0xB3, //!< ESC protection actions
PKT_ESC_RPM_LOOP_SETTINGS = 0xB5, //!< RPM Control Loop Settings
PKT_ESC_STARTING_SETTINGS, //!< ESC auto-starting configuration for RPM mode
PKT_ESC_CURRENT_CALIBRATION, //!< ESC current sense calibration settings
PKT_ESC_IO_TABLE_SETTINGS = 0xC0, //!< Configuration of the Input/Output mapping
PKT_ESC_IO_TABLE_ELEMENT, //!< A single element of the Input/Output mapping table
PKT_ESC_THROTTLE_CURVE = 0xC2, //!< Throttle curve calibration
PKT_ESC_PWM_INPUT_CALIBRATION = 0xC3,//!< PWM input calibration
PKT_ESC_BULK_TRANSFER = 0xF0 //!< Bulk data transfer (long packets)
} ESCPackets;
//! \return the label of a 'ESCPackets' enum entry, based on its value
const char* ESCPackets_EnumLabel(int value);
/*!
* ESC System Commands
*/
typedef enum
{
CMD_ESC_SET_NODE_ID = 0x50, //!< Set the CAN Node ID for the target ESC
CMD_ESC_SET_USER_ID_A, //!< Set user ID A value
CMD_ESC_SET_USER_ID_B, //!< Set user ID B value
CMD_ESC_TARE_CURRENT = 0x60, //!< Tare the current measurement
CMD_ESC_IDENTIFY = 0x70, //!< Identify the ESC with a sequence of LED flashes / beeps
CMD_ESC_REQUEST_HF_DATA = 0xB0, //!< Request high-frequency telemetry data
CMD_ESC_CONFIGURE_IO_MAP = 0xC0, //!< Configure the Input/Output map for the ESC
CMD_ESC_CONFIGURE_IO_ELEMENT, //!< Configure (or request) a particular element of the I/O map
CMD_ESC_RESET_SETTINGS = 0xD0, //!< Reset ESC settings to default parameters
CMD_ESC_ENTER_DEBUG = 0xDE, //!< Enter debug mode
CMD_ESC_EXIT_DEBUG, //!< Exit debug mode
CMD_ESC_UNLOCK_SETTINGS = 0xF5, //!< Unlock ESC nonvolatile settings
CMD_ESC_LOCK_SETTINGS = 0xF6, //!< Lock ESC nonvolatile settings
CMD_ESC_VALIDATE_SETTINGS = 0xF7, //!< Mark the current settings as valid
CMD_ESC_RESET_MOTOR_RUN_TIME = 0xFA, //!< Reset motor run time
CMD_ESC_ENTER_BOOTLOADER = 0xFB, //!< Enter bootloader mode
CMD_ESC_RESET //!< Reset ESC
} ESCSystemCommands;
//! \return the label of a 'ESCSystemCommands' enum entry, based on its value
const char* ESCSystemCommands_EnumLabel(int value);
// The prototypes below provide an interface to the packets.
// They are not auto-generated functions, but must be hand-written
@ -230,4 +439,4 @@ uint32_t getESCVelocityPacketID(const void* pkt);
#ifdef __cplusplus
}
#endif
#endif
#endif // _ESCVELOCITYPROTOCOL_H

View File

@ -0,0 +1,552 @@
<Protocol api="61" comment="This is the ICD for the Gen-2 Currawong Engineering Electronic Speed Controller (ESCVelocity). This document details the ESCVelocity command and packet structure for communication with and configuration of the ESC. Note that there may be some differences between this ICD and the ICD for the Gen-1 ESCVelocity. Please refer to the old ICD for the Gen-1 device." endian="big" file="ESCPackets" mapfile="ESC_SettingsMap" name="ESCVelocity" prefix="ESC_" supportBool="true" supportFloat64="false" supportInt64="false" supportSpecialFloat="false" verifyfile="ESC_SettingsVerify" version="3.40"><Include comment="C string manipulation function header" global="true" name="string.h" />
<Enum comment="Constant values required for sending a disable (inhibit) command" description="These values are required for the DISABLE command" name="ESCDisableSequence">
<Value comment="Constant value required for disabling the ESC" name="ESC_DISABLE_A" value="0xAA" />
<Value comment="Constant value required for disabling the ESC" name="ESC_DISABLE_B" value="0xC3" />
</Enum>
<Enum comment="Constant values required for sending an enable command" description="These values are required for the ENABLE command" name="ESCEnableSequence">
<Value comment="Constant value required for enabling the ESC" name="ESC_ENABLE_A" value="0xAA" />
<Value comment="Constant value required for enabling the ESC" name="ESC_ENABLE_B" value="0x3C" />
</Enum>
<Enum comment="ESC Operational Modes" description="These values define the various modes of operation of the ESC" lookup="true" name="ESCOperatingModes" prefix="ESC_MODE_">
<Value comment="ESC is in standby mode - the motor is OFF but the ESC is ready to accept motor commands" name="STANDBY" value="0x00" />
<Value comment="ESC is controlling motor in open-loop mode based on a 'PWM' (Pulse Width) input" name="PWM" />
<Value comment="ESC is controlling motor speed based on an RPM setpoint" name="RPM" />
<Value comment="ESC mode counter" ignorePrefix="true" name="ESC_VALID_MODES" />
</Enum>
<Enum comment="ESC Command Sources" description="These values define the source that the ESC has received its most recent valid command from" lookup="true" name="ESCCommandSources" prefix="ESC_COMMAND_SOURCE_">
<Value comment="No valid command has been received" name="NONE" value="0x00" />
<Value comment="Most recent command from CAN" name="CAN" />
<Value comment="Most recent command from PWM" name="PWM" />
</Enum>
<Enum comment="ESC motor temperature sensor options" description="These values define the supported motor temperature sensors" lookup="true" name="ESCMotorTemperatureSensor" prefix="ESC_MOTOR_TEMP_SENSOR_">
<Value comment="No temperature sensor selected" name="OFF" value="0x00" />
<Value comment="KTY84 or equivalent" name="KTY84" />
<Value comment="KTY83 or equivalent" name="KTY83" />
<Value comment="Use a custom temperature lookup table" name="CUSTOM" />
</Enum>
<Enum comment="ESC Command Priorities" lookup="true" name="ESCCommandPriorities" prefix="ESC_COMMAND_PRIORITY_">
<Value comment="Commands only from CAN, PWM hardware input is disabled" name="CAN_ONLY" value="0x00" />
<Value comment="Commands from CAN or PWM hardware input, CAN takes priority" name="CAN_PRIORITY" />
<Value comment="Commands from CAN or PWM hardware input, PWM takes priority" name="PWM_PRIORITY" />
</Enum>
<Enum comment="Motor direction" lookup="true" name="ESCMotorDirection" prefix="ESC_MOTOR_DIR_">
<Value comment="Motor phase sequence A / B / C" name="ABC" value="0" />
<Value comment="Motor phase sequence A / C / B" name="ACB" value="1" />
<Value comment="Unknown / unsupported direction" name="OTHER" value="3" />
</Enum>
<Enum comment="Hall sensor modes" lookup="true" name="ESCHallSensorMode" prefix="ESC_HALL_MODE_">
<Value comment="Sensorless control only" name="SENSORLESS" value="0" />
<Value comment="Sensored control only" name="SENSORED" value="1" />
<Value comment="Sensored starting transitioning to sensorless running" name="SENSORED_STARTING" value="2" />
</Enum>
<Enum comment="AFW operation modes" lookup="true" name="ESCAFWModes" prefix="ESC_AFW_MODE_">
<Value comment="AFW always off (during this motor running state)" name="OFF" value="0" />
<Value comment="AFW always on (during this motor running state)" name="ON" value="1" />
<Value comment="AFW may change state" name="DYNAMIC" value="2" />
<Value comment="Future expansion" name="OTHER" value="3" />
</Enum>
<Enum comment="PWM operation modes" lookup="true" name="ESCPWMFreqModes" prefix="ESC_PWM_FREQ_">
<Value comment="PWM frequency is the specified value" name="FIXED" value="0" />
<Value comment="" name="RAMP" value="1" />
<Value comment="Future expansion" name="OTHER" value="3" />
</Enum>
<Enum comment="PWM operation modes" lookup="true" name="ESCTimingAdvanceModes" prefix="ESC_TIMING_ADVANCE_MODE_">
<Value comment="Timing advance is the specified value" name="FIXED" value="0" />
<Value comment="" name="RAMP" value="1" />
<Value comment="Future expansion" name="OTHER" value="3" />
</Enum>
<Enum comment="ESC protection actions" lookup="true" name="ESCProtectionActions" prefix="ESC_PROTECTION_">
<Value comment="Warning bit is set" name="WARNING" value="0" />
<Value comment="Motor duty cycle is limited" name="FOLDBACK" value="1" />
<Value comment="ESC is disabled" name="DISABLE" value="2" />
<Value comment="Invalid protection action" name="INVALID" value="7" />
</Enum>
<Enum comment="Motor beep modes enumeration" lookup="true" name="ESCBeepModes" prefix="ESC_BEEP_">
<Value name="NONE" value="0b00" />
<Value comment="Motor status beeps only" name="STATUS" value="0b01" />
<Value comment="Motor error beeps only" name="ERROR" value="0b10" />
<Value comment="All motor beeps" name="ALL" value="0b11" />
</Enum>
<Enum comment="ESC standby cause flags" description="These flags indicate the cause(s) of an ESC standby event." lookup="true" name="ESCStandbyCause" prefix="ESC_STANDBY_CAUSE_">
<Value comment="ESC was put into *STANDBY* mode by a command" name="CMD" value="0x0001" />
<Value comment="ESC was put into *STANDBY* mode by SW or HW inhibit" name="INHIBIT" value="0x0002" />
<Value comment="ESC was put into *STANDBY* mode due to keepalive timeout" name="TIMEOUT" value="0x0004" />
<Value comment="ESC was put into *STANDBY* mode due to a hall sensor error" name="HALL_SENSOR_ERROR" value="0x0008" />
<Value comment="ESC was put into *STANDBY* mode due to a command being invalid" name="INVALID_CMD" value="0x0010" />
<Value comment="PWM arming signal detected" name="PWM_ARM" value="0x0020" />
<Value comment="ESC was put into *STANDBY* mode due to failed starting routine" name="FAILED_START" value="0x0040" />
<Value comment="ESC was put into *STANDBY* mode due to the received command below minimum threshold" name="MIN_CMD" value="0x0080" />
<Value comment="ESC was put into *STANDBY* mode due to failed resync routine" name="FAILED_RESYNC" value="0x0100" />
<Value comment="" name="RESET" value="0x8000" />
</Enum>
<Enum comment="ESC disable cause flags" description="These flags indicate the cause(s) of an ESC disable event." lookup="true" name="ESCDisableCause" prefix="ESC_DISABLE_CAUSE_">
<Value comment="Unused / blank value" name="NONE" value="0x0000" />
<Value comment="ESC is disabled by a CAN command" name="CAN_CMD" value="0x0001" />
<Value comment="PWM signal lost" name="PWM_TIMEOUT" value="0x0002" />
<Value comment="Hardware enable signal deasserted" name="HARDWARE" value="0x0004" />
<Value comment="ESC disabled due to overcurrent" name="OVERCURRENT" value="0x0008" />
<Value comment="ESC disabled due to overspeed" name="OVERSPEED" value="0x0010" />
<Value comment="ESC disabled due to overtemperature" name="OVERTEMP" value="0x0020" />
<Value comment="ESC disabled due to undervoltage" name="UNDERVOLTAGE" value="0x0040" />
<Value comment="ESC disabled due to starting failure (see ESCFailedStartCause for details)" name="FAILED_START" value="0x0080" />
<Value comment="ESC disabled due to commutation failure" name="COMMUTATION_ERROR" value="0x0100" />
<Value comment="ESC disabled due to invalid commutation state" name="INVALID_STATE" value="0x2000" />
<Value comment="ESC is disabled by processor reset" name="RESET" value="0x8000" />
</Enum>
<Enum comment="ESC motor OFF cause" description="These flags indicate the cause(s) of an ESC motor off event" lookup="true" name="ESCMotorOffCause" prefix="ESC_MOTOR_OFF_">
<Value comment="Motor turned off due to system standby" name="STANDBY" value="0x0001" />
<Value comment="Motor turned off due to beeping routine" name="BEEP" value="0x0002" />
<Value comment="Motor turned off at system initialisation" name="INITIALISE" value="0x0004" />
<Value comment="Motor turned off due to ESC being inhibited" name="INHIBITED" value="0x0010" />
<Value comment="Throttle below minimum value" name="THROTTLE_MIN" value="0x0020" />
<Value comment="Motor does not have valid commutation" name="NOT_RUNNING" value="0x0040" />
<Value comment="Starting routine failed" name="FAILED_START" value="0x0080" />
<Value comment="" name="INVALID" value="0x8000" />
</Enum>
<Enum comment="Failed start cause flags" description="These flags indicate the cause(s) of an ESC motor starting failure" lookup="true" name="ESCFailedStartCause" prefix="ESC_FAILED_START_CAUSE_">
<Value comment="No failed start has been recorded" name="RESET" value="0x0000" />
<Value comment="Starting procedure timed out" name="TIMEOUT" value="0x0001" />
<Value comment="Commutation speed too high" name="OVERSPEED" value="0x0002" />
<Value comment="Starting current exceeded" name="OVERCURRENT" value="0x0004" />
<Value comment="Motor is already spinning, in reverse direction" name="SPIN_REVERSED" value="0x0010" />
<Value comment="Motor is already spinning, above maximum catch speed" name="SPIN_TOO_FAST" value="0x0020" />
<Value comment="" name="INVALID" value="0x8000" />
</Enum>
<Enum comment="ESC Multi Command Packets" description="These packets can be used to send commands to 4 (four) ESCs with sequential CAN address identifiers, using a single CAN message. When sending these messages, they must be broadcast (using the special ESC broadcast address) so that each of the four target ESCs accept the CAN message." lookup="true" name="ESCMultiCommandPackets" prefix="PKT_ESC_">
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 1 - 4" name="SETPOINT_1" value="0" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 5 - 8" name="SETPOINT_2" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 9 - 12" name="SETPOINT_3" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 13 - 16" name="SETPOINT_4" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 17 - 20" name="SETPOINT_5" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 21 - 24" name="SETPOINT_6" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 25 - 28" name="SETPOINT_7" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 29 - 32" name="SETPOINT_8" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 33 - 36" name="SETPOINT_9" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 37 - 40" name="SETPOINT_10" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 41 - 44" name="SETPOINT_11" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 45 - 48" name="SETPOINT_12" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 49 - 52" name="SETPOINT_13" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 53 - 56" name="SETPOINT_14" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 57 - 60" name="SETPOINT_15" />
<Value comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 61 - 64" name="SETPOINT_16" />
</Enum>
<Enum comment="ESC Command Packets" description="Command packets are sent to the ESC to change its operational mode. These packets **must** be fully implemented in the connected avionics system for complete operation of the PCU" lookup="true" name="ESCCommandPackets" prefix="PKT_ESC_">
<Value comment="Send a PWM (Pulse width) command to a particular ESC" name="PWM_CMD" value="0x10" />
<Value comment="Send an RPM (Speed) command to a particular ESC" name="RPM_CMD" />
<Value comment="Send this packet to an ESC to disable the ESC" name="DISABLE" value="0x20" />
<Value comment="Send this packet to an ESC to enable the ESC and place it in Standby mode" name="STANDBY" />
</Enum>
<Enum comment="ESC Status Packets" description="Status packets are transmitted by the ESC at (user-configurable) intervals. These packets contain vital system information and should be fully implemented by the connected avionics device(s)." lookup="true" name="ESCStatusPackets" prefix="PKT_ESC_">
<Value comment="ESC Status A telemetry packet transmitted by the ESC at regular intervals" name="STATUS_A" value="0x80" />
<Value comment="ESC Status B telemetry packet transmitted by the ESC at regular intervals" name="STATUS_B" />
<Value comment="ESC Status C telemetry packet transmitted by the ESC at regular intervals (reserved for future use)" name="STATUS_C" />
<Value comment="Raw accelerometer data" name="ACCELEROMETER" value="0x88" />
</Enum>
<Enum comment="ESC Packets Definitions" description="ESC configuration packets. Each packet can be requested from the ESC by sending a zero-length packet of the same type." lookup="true" name="ESCPackets" prefix="PKT_ESC_">
<Value comment="Send a configuration command to the ESC (followed by optional command data bytes)" name="SYSTEM_CMD" value="0x50" />
<Value comment="Control loop output data - varies depending on the operational mode of the ESC" name="CONTROL_LOOP_DATA" value="0x8A" />
<Value comment="ESC warning / error status information." name="WARNINGS_ERRORS" value="0x86" />
<Value comment="Motor status flags" name="MOTOR_FLAGS" />
<Value comment="Event description packet" name="EVENT" value="0x8D" />
<Value comment="ESC Serial Number and User ID information" name="SERIAL_NUMBER" value="0x90" />
<Value comment="Human-readable string descriptor (max 8 chars) of the particular ESC" name="TITLE" />
<Value comment="ESC Firmware information" name="FIRMWARE" />
<Value comment="ESC system information packet" name="SYSTEM_INFO" />
<Value comment="Telemetry packet configuration" name="TELEMETRY_SETTINGS" />
<Value comment="ESC non-volatile data information and settings" name="EEPROM" />
<Value comment="ESC commissioning data (factory only)" hidden="true" name="COMMISSIONING" value="0x99" />
<Value comment="ESC telltales" name="TELLTALES" />
<Value comment="ESC firmware git hash" name="GIT_HASH" />
<Value comment="ESC motor configuration" hidden="true" name="LEGACY_MOTOR_SETTINGS" value="0xA5" />
<Value comment="ESC motor control firmware information" hidden="true" name="LEGACY_MOTOR_FIRMWARE" value="0xAA" />
<Value comment="Motor control settings packet" name="MOTOR_SETTINGS" value="0xA7" />
<Value comment="Motor starting settings packet" name="MOTOR_STARTING" value="0xA8" />
<Value comment="Motor and system parameters" name="MOTOR_PARAMETERS" value="0xA9" />
<Value comment="ESC Configuration parameters" name="CONFIG" value="0xB0" />
<Value comment="ESC protection values" name="PROTECTION_LEVELS" value="0xB2" />
<Value comment="ESC protection actions" name="PROTECTION_ACTIONS" value="0xB3" />
<Value comment="RPM Control Loop Settings" name="RPM_LOOP_SETTINGS" value="0xB5" />
<Value comment="ESC current sense calibration settings" hidden="true" name="CURRENT_CALIBRATION" />
<Value comment="A single element of the Input/Output mapping table" hidden="true" name="IO_TABLE_ELEMENT" />
<Value comment="Throttle curve calibration" name="THROTTLE_CURVE" value="0xC2" />
<Value comment="PWM input calibration" name="PWM_INPUT_CALIBRATION" value="0xC3" />
</Enum>
<Enum comment="ESC System Commands" description="These commands can be sent using the ESC_SYSTEM_CMD packet. Read further in this document for information on individual command packets." lookup="true" name="ESCSystemCommands" prefix="CMD_ESC_">
<Value comment="Set the CAN Node ID for the target ESC" name="SET_NODE_ID" value="0x50" />
<Value comment="Set user ID A value" name="SET_USER_ID_A" />
<Value comment="Set user ID B value" name="SET_USER_ID_B" />
<Value comment="Tare the current measurement" name="TARE_CURRENT" value="0x60" />
<Value comment="Identify the ESC with a sequence of LED flashes / beeps" name="IDENTIFY" value="0x70" />
<Value comment="Request high-frequency telemetry data" name="REQUEST_HF_DATA" value="0xB0" />
<Value comment="Configure the Input/Output map for the ESC" name="CONFIGURE_IO_MAP" value="0xC0" />
<Value comment="Configure (or request) a particular element of the I/O map" name="CONFIGURE_IO_ELEMENT" />
<Value comment="Reset ESC settings to default parameters" name="RESET_SETTINGS" value="0xD0" />
<Value comment="Exit debug mode" hidden="true" name="EXIT_DEBUG" />
<Value comment="Unlock ESC nonvolatile settings" name="UNLOCK_SETTINGS" value="0xF5" />
<Value comment="Lock ESC nonvolatile settings" name="LOCK_SETTINGS" />
<Value comment="Reset motor run time" name="RESET_MOTOR_RUN_TIME" value="0xFA" />
<Value comment="Enter bootloader mode" name="ENTER_BOOTLOADER" value="0xFB" />
<Value comment="Reset ESC" name="RESET" />
</Enum>
<Structure comment="The *status* of the ESC is represented using these status bits. ESC system functionality can be quickly determined using these bits" file="ESCDefines" map="false" name="StatusBits">
<Data comment="Set if hardware inhibit is active (ESC is disabled)" encodedType="bitfield1" inMemoryType="bool" name="hwInhibit" />
<Data comment="Set if software inhibit is active (ESC is disabled)" encodedType="bitfield1" inMemoryType="bool" name="swInhibit" />
<Data comment="Set if Active Freewheeling is currently active" encodedType="bitfield1" inMemoryType="bool" name="afwEnabled" />
<Data comment="0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE" encodedType="bitfield1" inMemoryType="unsigned8" name="direction" />
<Data comment="Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)" encodedType="bitfield1" inMemoryType="bool" name="timeout" />
<Data comment="Set if ESC is in starting mode (Cleared if ESC is stopped or running)" encodedType="bitfield1" inMemoryType="bool" name="starting" />
<Data comment="0 = most recent command from CAN, 1 = most recent command from PWM" encodedType="bitfield1" inMemoryType="unsigned8" name="commandSource" />
<Data comment="Set if ESC is running" encodedType="bitfield1" inMemoryType="bool" name="running" />
<Data comment="Warning active - refer to the PKT_ESC_WARNINGS_ERRORS packet" encodedType="bitfield1" inMemoryType="bool" name="anyWarnings" />
<Data comment="Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet" encodedType="bitfield1" inMemoryType="bool" name="anyErrors" />
<Data comment="Reserved bits for future use" constant="0" encodedType="bitfield5" inMemoryType="null" name="reservedBitsA" />
<Data comment="Set if the motor is spinning (even if it is not being driven)" encodedType="bitfield1" inMemoryType="bool" name="spinning" />
<Data comment="Set if motor is spinning opposite to configured rotation direction" encodedType="bitfield1" inMemoryType="bool" name="spinningReversed" />
<Data comment="Set if motor duty cycle is being limited due to ESC protection settings" encodedType="bitfield1" inMemoryType="bool" name="foldback" />
<Data comment="Set if the ESC is attempting to sync with the motor" encodedType="bitfield1" inMemoryType="bool" name="syncing" />
<Data comment="Reserved bits for future use" constant="0" encodedType="bitfield4" inMemoryType="null" name="reservedBitsC" />
<Data comment="Set if the ESC is in debug mode (factory use only)" encodedType="bitfield1" inMemoryType="bool" name="debug" />
</Structure>
<Structure comment="The *warning* bits enumerate various system warnings/errors of which the user (or user software) should be made aware. These *warning* bits are transmitted in the telemetry packets such that user software is aware of any these *warning* conditions and can poll the ESC for particular packets if any further information is needed. The ESC will continue to function in the case of a *warning* state" file="ESCDefines" map="false" name="WarningBits">
<Data comment="Reserved for future use" constant="0" encodedType="bitfield1" inMemoryType="bool" name="reserved" />
<Data comment="Set if the ESC motor speed exceeds the configured warning threshold" encodedType="bitfield1" inMemoryType="bool" name="overspeed" />
<Data comment="Set if the ESC motor current (positive or negative) exceeds the configured warning threshold" encodedType="bitfield1" inMemoryType="bool" name="overcurrent" />
<Data comment="Set if the internal ESC temperature is above the warning threshold" encodedType="bitfield1" inMemoryType="bool" name="escTemperature" />
<Data comment="Set if the motor temperature is above the warning threshold" encodedType="bitfield1" inMemoryType="bool" name="motorTemperature" />
<Data comment="Set if the input voltage is below the minimum threshold" encodedType="bitfield1" inMemoryType="bool" name="undervoltage" />
<Data comment="Set if the input voltage is above the maximum threshold" encodedType="bitfield1" inMemoryType="bool" name="overvoltage" />
<Data comment="Set if hardware PWM input is enabled but invalid" encodedType="bitfield1" inMemoryType="bool" name="invalidPWMsignal" />
<Data comment="Set if the motor demag angle exceeds the maximum threshold" encodedType="bitfield1" inMemoryType="bool" name="demagAngle" />
<Data comment="Set if the auto-advance exceeds 25 degrees" encodedType="bitfield1" inMemoryType="bool" name="advanceLimit" />
<Data comment="Set if the measured demag pulse is exceptionally long" encodedType="bitfield1" inMemoryType="bool" name="longDemag" />
<Data comment="Set if a zero-crossing measurement was missed" encodedType="bitfield1" inMemoryType="bool" name="missedZeroCrossing" />
<Data comment="Motor is spinning in the wrong direction" encodedType="bitfield1" inMemoryType="bool" name="spinningReversed" />
<Data comment="Motor has reached maximum allowable commutation speed" encodedType="bitfield1" inMemoryType="bool" name="commSpeedLimit" />
<Data comment="Reserved for future use" constant="0" encodedType="bitfield2" inMemoryType="null" name="reservedBits" />
</Structure>
<Structure comment="The *error* bits enumerate critical system errors that will cause the ESC to stop functioning until the error cases are alleviated" file="ESCDefines" map="false" name="ErrorBits">
<Data comment="Set if the ESC failed to start the motor" encodedType="bitfield1" inMemoryType="unsigned8" name="failedStart" />
<Data comment="Lost commutation" encodedType="bitfield1" inMemoryType="unsigned8" name="commutation" />
<Data comment="Set if hall sensor error detected" encodedType="bitfield1" inMemoryType="unsigned8" name="hallSensor" />
<Data comment="Current exceeded hard-limit" encodedType="bitfield1" inMemoryType="unsigned8" name="overcurrent" />
<Data comment="Temperature exceeded hard-limit" encodedType="bitfield1" inMemoryType="unsigned8" name="overtemperature" />
<Data comment="Motor commutation speed exceeded hard-limit" encodedType="bitfield1" inMemoryType="unsigned8" name="overspeed" />
<Data comment="Motor stopped due to high demag angle" encodedType="bitfield1" inMemoryType="unsigned8" name="demag" />
<Data comment="Reserved for future use" constant="0" encodedType="unsigned8" inMemoryType="null" name="reserved" />
</Structure>
<Structure comment="These bits are used to determine which packets are automatically transmitted as telemetry data by the ESC. Only the packets described here can be configured as telemetry packets" file="ESCDefines" map="true" name="TelemetryPackets">
<Data comment="If this bit is set, the STATUS_A packet will be transmitted at the configured rate" encodedType="bitfield1" inMemoryType="bool" initialValue="1" name="statusA" />
<Data comment="If this bit is set, the STATUS_B packet will be transmitted at the configured rate" encodedType="bitfield1" inMemoryType="bool" initialValue="1" name="statusB" />
<Data comment="If this bit is set, the STATUS_C packet will be transmitted at the configured rate" encodedType="bitfield1" inMemoryType="bool" initialValue="1" name="statusC" />
<Data comment="If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate" encodedType="bitfield1" inMemoryType="bool" initialValue="0" name="accelerometer" />
<Data comment="If this bit is set, the STATUS_D packet will be transmitted at the configured rate" encodedType="bitfield1" inMemoryType="bool" name="statusD" />
<Data comment="Reserved for future use" encodedType="bitfield1" inMemoryType="bool" name="reservedTelemA" />
<Data comment="If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)" encodedType="bitfield1" inMemoryType="bool" name="piccoloDownlink" />
<Data comment="Reserved for future use" encodedType="bitfield1" inMemoryType="bool" name="reservedTelemC" />
</Structure>
<Structure comment="These bits are used to select which debug packets are transmitted at high-frequency by the ESC" file="ESCDefines" name="DebugPackets">
<Data comment="Control loop terms" default="0" encodedType="bitfield1" inMemoryType="bool" name="ctrlLoopOutputs" />
<Data comment="Hall sensor debug information" default="0" encodedType="bitfield1" inMemoryType="bool" name="hallSensors" />
<Data comment="Commutation debug information" default="0" encodedType="bitfield1" inMemoryType="bool" name="commutation" />
<Data comment="Demag debug information" default="0" encodedType="bitfield1" inMemoryType="bool" name="demag" />
<Data comment="PWM input debug information" default="0" encodedType="bitfield1" inMemoryType="bool" name="pwmInput" />
<Data comment="Reserved for future use" constant="0" default="0" encodedType="bitfield3" inMemoryType="null" name="reservedA" />
<Data comment="Reserved for future use" constant="0" default="0" encodedType="unsigned8" inMemoryType="null" name="reservedB" />
</Structure>
<Packet ID="PKT_ESC_SETPOINT_1" comment="Send this packet to command ESCs which have CAN ID values in the range {1,4} (inclusive). This packet must be sent as a broadcast packet (address = 0xFF) such that all ESCs can receive it. Similiar commands are available for commanding ESCs with ID values up to 64, using different ESC_SETPOINT_x packet ID values." name="CommandMultipleESCs" parameterInterface="true">
<Data comment="The PWM (pulse width) command for ESC with CAN ID 1" inMemoryType="unsigned16" name="pwmValueA" units="1us per bit" />
<Data comment="The PWM (pulse width) command for ESC with CAN ID 2" inMemoryType="unsigned16" name="pwmValueB" units="1us per bit" />
<Data comment="The PWM (pulse width) command for ESC with CAN ID 3" inMemoryType="unsigned16" name="pwmValueC" units="1us per bit" />
<Data comment="The PWM (pulse width) command for ESC with CAN ID 4" inMemoryType="unsigned16" name="pwmValueD" units="1us per bit" />
</Packet>
<Packet ID="PKT_ESC_DISABLE" comment="Send this packet to the ESC to disable it. The ESC will not accept PWM/RPM commands until it is re-enabled." name="Disable" parameterInterface="true">
<Data checkConstant="true" comment="This value must be set for the command to be accepted" constant="ESC_DISABLE_A" encodedType="unsigned8" inMemoryType="null" name="disableSequenceA" />
<Data checkConstant="true" comment="This value must be set for the command to be accepted" constant="ESC_DISABLE_B" encodedType="unsigned8" inMemoryType="null" name="disableSequenceB" />
</Packet>
<Packet ID="PKT_ESC_STANDBY" comment="Send this packet to the ESC to enable it. The ESC will be placed in Standby mode." name="Enable" parameterInterface="true">
<Data checkConstant="true" comment="This value must be set for the command to be accepted" constant="ESC_ENABLE_A" encodedType="unsigned8" inMemoryType="null" name="enableSequenceA" />
<Data checkConstant="true" comment="This value must be set for the command to be included" constant="ESC_ENABLE_B" encodedType="unsigned8" inMemoryType="null" name="enableSequenceB" />
</Packet>
<Packet ID="PKT_ESC_PWM_CMD" comment="Send a PWM (pulse width) command to an individual ESC. The pulse width value in specified in microseconds for compatibility with standard ESC interface. Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus." name="PWMCommand" parameterInterface="true">
<Data comment="PWM command" inMemoryType="unsigned16" name="pwmCommand" units="1us per bit" />
</Packet>
<Packet ID="PKT_ESC_RPM_CMD" comment="Send an RPM (speed) command to an individual ESC. Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus" name="RPMCommand" parameterInterface="true">
<Data comment="RPM Command" inMemoryType="unsigned16" name="rpmCommand" units="RPM" />
</Packet>
<Packet ID="PKT_ESC_STATUS_A" comment="The ESC_STATUS_A packet contains high-priority ESC status information. This packet is transmitted by the ESC at regular (user-configurable) intervals. It can also be requested (polled) from the ESC by sending a zero-length packet of the same type." map="false" name="StatusA" parameterInterface="true">
<Data checkConstant="true" comment="Set to 1 to indicate a Gen-2 ESC" constant="1" encodedType="bitfield1" inMemoryType="null" name="version" />
<Data comment="Reserved for future use" constant="0" encodedType="bitfield3" inMemoryType="null" name="reservedA" />
<Data comment="ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper three bits are used for debugging and should be ignored for general use." encodedType="bitfield4" inMemoryType="unsigned8" name="mode" />
<Data comment="ESC status bits" name="status" struct="StatusBits" />
<Data comment="ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM" inMemoryType="unsigned16" name="command" />
<Data comment="Motor speed" inMemoryType="unsigned16" name="rpm" units="1RPM per bit" />
</Packet>
<Packet ID="PKT_ESC_STATUS_B" comment="The ESC_STATUS_B packet contains ESC operational information. This packet is transmitted by the ESC at regular (user-configurable) intervals. It can also be requested (polled) from the ESC by sending a zero-length packet of the same type." map="false" name="StatusB" parameterInterface="true">
<Data comment="ESC Rail Voltage" inMemoryType="unsigned16" name="voltage" units="0.1V per bit" />
<Data comment="ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative" inMemoryType="signed16" name="current" units="0.1A per bit" />
<Data comment="ESC Motor Duty Cycle" inMemoryType="unsigned16" name="dutyCycle" units="0.1% per bit" />
<Data comment="ESC Logic Board Temperature" inMemoryType="signed8" name="escTemperature" range="-128C to +127C" units="1 degree C per bit" />
<Data comment="ESC Motor Temperature" inMemoryType="unsigned8" name="motorTemperature" range="-50 to +205 (0 = -50C)" units="1 degree C per bit" />
</Packet>
<Packet ID="PKT_ESC_STATUS_C" map="false" name="StatusC" parameterInterface="true">
<Data comment="Reserved for future use" constant="0" encodedType="signed16" inMemoryType="null" name="reserved" />
<Data comment="ESC Phase Board Temperature" encodedType="unsigned8" inMemoryType="float" max="205" min="-50" name="fetTemperature" />
<Data comment="Current motor PWM frequency (10 Hz per bit)" inMemoryType="unsigned16" name="pwmFrequency" />
<Data comment="Current timing advance (0.1 degree per bit)" inMemoryType="unsigned16" name="timingAdvance" />
</Packet>
<Packet ID="PKT_ESC_ACCELEROMETER" comment="This packet contains raw accelerometer data from the ESC. It can be requested (polled) from the ESC by sending a zero-length packet of the same type. It can also be transmitted by the ESC at high-frequency using the high-frequency streaming functionality of the ESC" map="false" name="Accelerometer" parameterInterface="true">
<Data comment="X axis acceleration value" inMemoryType="signed16" name="xAcc" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units" range="-0x7FFF to +0x7FFF" />
<Data comment="Y axis acceleration value" inMemoryType="signed16" name="yAcc" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units" range="-0x7FFF to +0x7FFF" />
<Data comment="Z axis acceleration value" inMemoryType="signed16" name="zAcc" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units" range="-0x7FFF to +0x7FFF" />
<Data comment="Accelerometer full-scale range" inMemoryType="unsigned8" name="fullscale" />
<Data comment="Accelerometer measurement resolution, in 'bits'." inMemoryType="unsigned8" name="resolution" />
</Packet>
<Packet ID="PKT_ESC_WARNINGS_ERRORS" comment="Warning and error status information" map="false" name="WarningErrorStatus" parameterInterface="true" structureInterface="true">
<Data name="warnings" struct="WarningBits" />
<Data name="errors" struct="ErrorBits" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" comment="Set the CAN Node ID of the target ESC" file="ESCCommands" map="false" name="SetNodeID" parameterInterface="true">
<Data checkConstant="true" constant="CMD_ESC_SET_NODE_ID" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data comment="The serial number must match that of the target ESC for the command to be accepted" inMemoryType="unsigned32" name="serialNumber" />
<Data comment="The new Node ID of the ESC" inMemoryType="unsigned8" name="nodeID" notes="An ESC with a Node ID of zero (0) will be disabled" range="0 to 254" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" comment="Set User ID A" file="ESCCommands" map="false" name="SetUserIDA" parameterInterface="true">
<Data checkConstant="true" constant="CMD_ESC_SET_USER_ID_A" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data comment="" inMemoryType="unsigned16" name="id" units="" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" comment="Set User ID B" file="ESCCommands" map="false" name="SetUserIDB" parameterInterface="true">
<Data checkConstant="true" constant="CMD_ESC_SET_USER_ID_B" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data comment="" inMemoryType="unsigned16" name="id" units="" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" file="ESCCommands" map="false" name="UnlockSettings">
<Data checkConstant="true" constant="CMD_ESC_UNLOCK_SETTINGS" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data checkConstant="true" constant="0xA0" encodedType="unsigned8" inMemoryType="null" name="unlockSeqA" />
<Data checkConstant="true" constant="0xB0" encodedType="unsigned8" inMemoryType="null" name="unlockSeqB" />
<Data checkConstant="true" constant="0xC0" encodedType="unsigned8" inMemoryType="null" name="unlockSeqC" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" file="ESCCommands" map="false" name="LockSettings">
<Data checkConstant="true" constant="CMD_ESC_LOCK_SETTINGS" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data checkConstant="true" constant="0x0A" encodedType="unsigned8" inMemoryType="null" name="lockSeqA" />
<Data checkConstant="true" constant="0x0B" encodedType="unsigned8" inMemoryType="null" name="lockSeqB" />
<Data checkConstant="true" constant="0x0C" encodedType="unsigned8" inMemoryType="null" name="lockSeqC" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" file="ESCCommands" map="false" name="ResetMotorRunTime">
<Data checkConstant="true" constant="CMD_ESC_RESET_MOTOR_RUN_TIME" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data checkConstant="true" comment="This byte is required for the command to be accepted" constant="0xAB" encodedType="unsigned8" inMemoryType="null" name="resetSeqA" />
<Data checkConstant="true" comment="This byte is required for the command to be accepted" constant="0xCD" encodedType="unsigned8" inMemoryType="null" name="resetSeqA" />
<Data comment="Serial number must match ESC" inMemoryType="unsigned16" name="serialNumber" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" file="ESCCommands" map="false" name="EnterBootloader">
<Data checkConstant="true" constant="CMD_ESC_ENTER_BOOTLOADER" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data checkConstant="true" comment="This byte is required for the command to be accepted" constant="0xAA" encodedType="unsigned8" inMemoryType="null" name="bootSeqA" />
<Data checkConstant="true" comment="This byte is required for the command to be accepted" constant="0x55" encodedType="unsigned8" inMemoryType="null" name="bootSeqB" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_CMD" file="ESCCommands" map="false" name="ResetESC">
<Data checkConstant="true" constant="CMD_ESC_RESET" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data checkConstant="true" comment="This byte is required for the command to be accepted" constant="0xAA" encodedType="unsigned8" inMemoryType="null" name="resetSeqA" />
<Data checkConstant="true" comment="This byte is required for the command to be accepted" constant="0xCC" encodedType="unsigned8" inMemoryType="null" name="resetSeqB" />
</Packet>
<Packet ID="PKT_ESC_MOTOR_FLAGS" comment="Motor status flags" name="MotorStatusFlags" parameterInterface="true" structureInterface="true">
<Data comment="Cause of most recent standby event" enum="ESCStandbyCause" inMemoryType="unsigned16" name="standbyCause" />
<Data comment="Cause of most recent disable event" enum="ESCDisableCause" inMemoryType="unsigned16" name="disableCause" />
<Data comment="Cause of most recent motor-stop event" enum="ESCMotorOffCause" inMemoryType="unsigned16" name="offCause" />
<Data comment="Cause of most recent failed-start" enum="ESCFailedStartCause" inMemoryType="unsigned16" name="failedStartCause" />
</Packet>
<Packet ID="PKT_ESC_CONFIG" comment="General ESC configuration parameters" map="true" name="Config" parameterInterface="true" structureInterface="true" useInOtherPackets="true">
<Data comment="1 = ESC is inhibited (disabled) on startup" encodedType="bitfield1" inMemoryType="bool" initialValue="1" name="swInhibit" />
<Data comment="1 = ESC will respond to PICCOLO autopilot commands" encodedType="bitfield1" inMemoryType="bool" initialValue="1" name="piccoloCommands" />
<Data comment="1 = ESC will accept broadcast command messages" encodedType="bitfield1" inMemoryType="bool" initialValue="1" name="broadcastCommands" />
<Data comment="Command input source priority, refer to enumeration ESCCommandPriorities" encodedType="bitfield2" inMemoryType="unsigned8" initialValue="ESC_COMMAND_PRIORITY_CAN_PRIORITY" name="commandInputPriority" />
<Data comment="Reserved for future use" constant="0" encodedType="bitfield1" inMemoryType="null" name="reserved" />
<Data comment="External motor temperature sensor configuration" encodedType="bitfield2" inMemoryType="unsigned8" name="motorTempSensor" />
<Data comment="ESC keepalive timeout - If this is non-zero, the ESC will automatically revert to *STANDBY* mode if it does not receive a valid command for the alloted period" inMemoryType="unsigned8" initialValue="100" name="keepalive" notes="0 = No timeout" range="0 to 250 (0.0s to 25.0s)" units="100ms per bit" verifyMaxValue="250" />
<Data comment="Reserved for future use" encodedType="unsigned8" inMemoryType="null" name="reservedA" />
<Data comment="Reserved for future use" encodedType="unsigned8" inMemoryType="null" name="reservedB" />
<Data comment="Reserved for future use" encodedType="unsigned8" inMemoryType="null" name="reservedC" />
<Data comment="Reserved for future use" encodedType="unsigned16" inMemoryType="null" name="reservedD" />
<Data encodedType="bitfield3" inMemoryType="unsigned8" initialValue="ESC_BEEP_ALL" name="motorBeepMode" />
<Data comment="Motor beep volume" encodedType="bitfield5" inMemoryType="unsigned8" initialValue="20" name="motorBeepVolume" units="5% per bit" verifyMaxValue="30" verifyMinValue="1" />
</Packet>
<Packet ID="PKT_ESC_SERIAL_NUMBER" comment="This packet contains the serial number for the ESC. Additionally there are two extra values (each 16-bit) which can be programmed by the user for any purpose." name="Address" packetType="config" parameterInterface="true">
<Data comment="ESC hardware revision (OTP - not configurable by user)" inMemoryType="unsigned8" name="HardwareRevision" />
<Data comment="ESC model (OTP - not configurable by user)" inMemoryType="unsigned8" name="Model" />
<Data comment="ESC Serial Number (OTP - not configurable by user)" inMemoryType="unsigned16" name="SerialNumber" />
<Data comment="User ID Value A - user can set this value to any value" inMemoryType="unsigned16" name="UserIDA" />
<Data comment="User ID Value B - user can set this value to any value" inMemoryType="unsigned16" name="UserIDB" />
</Packet>
<Packet ID="PKT_ESC_TITLE" comment="This packet contains a zero-terminated string (max-length 8) used to identify the particular ESC." name="Title" parameterInterface="true">
<Data array="8" comment="Description of this ESC" inMemoryType="unsigned8" name="ESCTitle" />
</Packet>
<Packet ID="PKT_ESC_FIRMWARE" comment="This packet contains the firmware version of the ESC" name="Firmware" packetType="config" parameterInterface="true">
<Data comment="Major firmware version number" inMemoryType="unsigned8" name="versionMajor" />
<Data comment="Minor firmware version numner" inMemoryType="unsigned8" name="versionMinor" />
<Data comment="Firmware release date, day-of-month" inMemoryType="unsigned8" name="versionDay" range="1-31" />
<Data comment="Firmware release data, month-of-year" inMemoryType="unsigned8" name="versionMonth" range="1-12" />
<Data comment="Firmware release date, year" inMemoryType="unsigned16" name="versionYear" />
<Data comment="Firmware checksum" inMemoryType="unsigned16" name="firmwareChecksum" />
</Packet>
<Packet ID="PKT_ESC_SYSTEM_INFO" comment="This packet contains system runtime information" name="SystemInfo" parameterInterface="true">
<Data comment="Number of milliseconds since the ESC last experienced a reset/power-on event" inMemoryType="unsigned32" name="millisecondsSinceReset" />
<Data comment="Number of power cycle events that the ESC has experienced" inMemoryType="unsigned16" name="powerCycles" />
<Data comment="Processor RESET code for debug purposes" inMemoryType="unsigned8" name="resetCode" />
<Data comment="Processor usage" inMemoryType="unsigned8" name="cpuOccupancy" units="1% per bit" />
</Packet>
<Packet ID="PKT_ESC_TELEMETRY_SETTINGS" comment="Telemetry settings (storage class)" name="TelemetryConfig" parameterInterface="true" structureInterface="true" useInOtherPackets="true">
<Data comment="Telemetry period code (maps indirectly to a telemetry period value)" inMemoryType="unsigned8" initialValue="74" name="period" notes="0 = Telemetry disabled" />
<Data comment="Telemetry silence period (delay after RESET before telemetry data is sent)" inMemoryType="unsigned8" initialValue="20" name="silence" range="0 - 250 (0.0s to 25.0s)" units="50ms per bit" verifyMaxValue="250" />
<Data comment="Bitfield describing which telemetry packets are enabled" name="packets" struct="TelemetryPackets" />
</Packet>
<Packet ID="PKT_ESC_TELEMETRY_SETTINGS" comment="This packet contains the telemetry packet configuration" name="TelemetrySettings" parameterInterface="true">
<Data comment="Telemetry settings" name="settings" struct="TelemetryConfig" />
<Data array="5" comment="The API version of the ESC" constant="getESCVelocityVersion()" inMemoryType="string" name="apiVersion" />
</Packet>
<Packet ID="PKT_ESC_EEPROM" comment="This packet contains information on the non-volatile ESC settings" name="EEPROMSettings" parameterInterface="true">
<Data comment="Set if the ESC settings are locked" encodedType="bitfield1" inMemoryType="unsigned8" name="settingsLocked" />
<Data comment="Version of EEPROM data" encodedType="bitfield1" inMemoryType="unsigned8" name="version" />
<Data comment="Size of settings data" inMemoryType="unsigned16" name="size" />
<Data comment="Settings checksum" inMemoryType="unsigned16" name="checksum" />
</Packet>
<Packet ID="PKT_ESC_TELLTALES" name="TelltaleValues" parameterInterface="true" structureInterface="true">
<Data comment="Maximum recorded internal temperature" inMemoryType="unsigned8" initialValue="0" name="maxTemperature" />
<Data comment="Maximum recorded MOSFET temperature" inMemoryType="unsigned8" initialValue="0" name="maxFetTemperature" />
<Data comment="Maximum recorded motor temperature" inMemoryType="unsigned8" initialValue="0" name="maxMotorTemperature" />
<Data comment="Maximum recorded battery voltage" default="0" inMemoryType="unsigned8" initialValue="0" name="maxRippleVoltage" />
<Data comment="Maximum recorded battery current" default="0" encodedType="signed16" inMemoryType="float" initialValue="0" name="maxBatteryCurrent" scaler="10" />
<Data comment="Maximum recorded regen current" default="0" encodedType="signed16" inMemoryType="float" initialValue="0" name="maxRegenCurrent" scaler="10" />
<Data comment="Number of successful motor start events" default="0" inMemoryType="unsigned16" initialValue="0" name="totalStarts" />
<Data comment="Number of failed motor start events" default="0" inMemoryType="unsigned16" initialValue="0" name="failedStarts" />
<Data comment="ESC run time" default="0" inMemoryType="unsigned32" initialValue="0" name="escRunTime" />
<Data comment="Motor run time" default="0" inMemoryType="unsigned32" initialValue="0" name="motorRunTime" />
<Data comment="Number of recorded motor desync events" default="0" inMemoryType="unsigned32" initialValue="0" name="desyncEvents" />
</Packet>
<Packet ID="PKT_ESC_GIT_HASH" comment="Git commit hash for the ESC firmware" name="GitHash">
<Data array="8" comment="git commit hash" inMemoryType="string" name="hash" />
</Packet>
<Packet ID="PKT_ESC_PWM_INPUT_CALIBRATION" file="ESCPackets" name="PWMInputCalibration" parameterInterface="true" structureInterface="true">
<Data comment="Protocol version (reserved for future use)" constant="0" inMemoryType="unsigned8" initialValue="0" name="protocol" />
<Data comment="PWM offset compensation value" inMemoryType="signed8" initialValue="0" name="pwmOffset" units="us" verifyMaxValue="125" verifyMinValue="-125" />
<Data comment="PWM value corresponding with 0% throttle" inMemoryType="unsigned16" initialValue="1000" name="inputMin" units="us" verifyMaxValue="2500" verifyMinValue="250" />
<Data comment="PWM value corresponding with 1000% throttle" inMemoryType="unsigned16" initialValue="2000" name="inputMax" units="us" verifyMaxValue="2500" verifyMinValue="250" />
<Data comment="PWM arming threshold" inMemoryType="unsigned16" initialValue="900" name="armThreshold" units="us" verifyMaxValue="2500" verifyMinValue="250" />
</Packet>
</Protocol>

View File

@ -0,0 +1,271 @@
// LegacyESCDefines.c was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#include "LegacyESCDefines.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Encode a ESC_LegacyStatusBits_t into a byte array
*
* Status bits associated with the legacy (gen-1) ESC
* \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 encodeESC_LegacyStatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_LegacyStatusBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = Hardware inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->hwInhibit << 7;
// 1 = Software inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->swInhibit << 6;
// 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->afwEnabled << 5;
// 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->direction << 4;
// Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->timeout << 3;
// 1 = in starting mode (0 = stopped or running)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->starting << 2;
// 0 = most recent command from CAN, 1 = most recent command from PWM
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->commandSource << 1;
// ESC is running
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->running;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_LegacyStatusBits_t
/*!
* \brief Decode a ESC_LegacyStatusBits_t from a byte array
*
* Status bits associated with the legacy (gen-1) ESC
* \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 decodeESC_LegacyStatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_LegacyStatusBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = Hardware inhibit is active (ESC is disabled)
_pg_user->hwInhibit = (_pg_data[_pg_byteindex] >> 7);
// 1 = Software inhibit is active (ESC is disabled)
_pg_user->swInhibit = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
_pg_user->afwEnabled = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
_pg_user->direction = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
_pg_user->timeout = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// 1 = in starting mode (0 = stopped or running)
_pg_user->starting = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// 0 = most recent command from CAN, 1 = most recent command from PWM
_pg_user->commandSource = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// ESC is running
_pg_user->running = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_LegacyStatusBits_t
/*!
* \brief Encode a ESC_LegacyWarningBits_t into a byte array
*
* Warning bits associated with the legacy (gen-1) ESC
* \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 encodeESC_LegacyWarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_LegacyWarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if RPM signal is not detected
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->noRPMSignal << 7;
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overspeed << 6;
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overcurrent << 5;
// Set if the internal ESC temperature is above the warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->escTemperature << 4;
// Set if the motor temperature is above the warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->motorTemperature << 3;
// Set if the input voltage is below the minimum threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->undervoltage << 2;
// Set if the input voltage is above the maximum threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overvoltage << 1;
// Set if hardware PWM input is enabled but invalid
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->invalidPWMsignal;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_LegacyWarningBits_t
/*!
* \brief Decode a ESC_LegacyWarningBits_t from a byte array
*
* Warning bits associated with the legacy (gen-1) ESC
* \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 decodeESC_LegacyWarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_LegacyWarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if RPM signal is not detected
_pg_user->noRPMSignal = (_pg_data[_pg_byteindex] >> 7);
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_user->overspeed = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
_pg_user->overcurrent = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// Set if the internal ESC temperature is above the warning threshold
_pg_user->escTemperature = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Set if the motor temperature is above the warning threshold
_pg_user->motorTemperature = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// Set if the input voltage is below the minimum threshold
_pg_user->undervoltage = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// Set if the input voltage is above the maximum threshold
_pg_user->overvoltage = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// Set if hardware PWM input is enabled but invalid
_pg_user->invalidPWMsignal = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_LegacyWarningBits_t
/*!
* \brief Encode a ESC_LegacyErrorBits_t into a byte array
*
* Error bits associated with the legacy (gen-1) ESC
* \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 encodeESC_LegacyErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_LegacyErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if communication link to the motor controller is lost
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->linkError << 7;
// Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->foldback << 6;
// Set if the settings checksum does not match the programmed values
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->settingsChecksum << 5;
// Set if the motor settings are invalid
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->motorSettings << 4;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedD << 3;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedE << 2;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedF << 1;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedG;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_LegacyErrorBits_t
/*!
* \brief Decode a ESC_LegacyErrorBits_t from a byte array
*
* Error bits associated with the legacy (gen-1) ESC
* \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 decodeESC_LegacyErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_LegacyErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if communication link to the motor controller is lost
_pg_user->linkError = (_pg_data[_pg_byteindex] >> 7);
// Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
_pg_user->foldback = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// Set if the settings checksum does not match the programmed values
_pg_user->settingsChecksum = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// Set if the motor settings are invalid
_pg_user->motorSettings = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Reserved for future use
_pg_user->reservedD = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// Reserved for future use
_pg_user->reservedE = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// Reserved for future use
_pg_user->reservedF = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// Reserved for future use
_pg_user->reservedG = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_LegacyErrorBits_t
// end of LegacyESCDefines.c

View File

@ -0,0 +1,109 @@
// LegacyESCDefines.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _LEGACYESCDEFINES_H
#define _LEGACYESCDEFINES_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
/*!
* Status bits associated with the legacy (gen-1) ESC
*/
typedef struct
{
unsigned hwInhibit : 1; //!< 1 = Hardware inhibit is active (ESC is disabled)
unsigned swInhibit : 1; //!< 1 = Software inhibit is active (ESC is disabled)
unsigned afwEnabled : 1; //!< 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
unsigned direction : 1; //!< 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
unsigned timeout : 1; //!< Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
unsigned starting : 1; //!< 1 = in starting mode (0 = stopped or running)
unsigned commandSource : 1; //!< 0 = most recent command from CAN, 1 = most recent command from PWM
unsigned running : 1; //!< ESC is running
}ESC_LegacyStatusBits_t;
//! return the minimum encoded length for the ESC_LegacyStatusBits_t structure
#define getMinLengthOfESC_LegacyStatusBits_t() (1)
//! return the maximum encoded length for the ESC_LegacyStatusBits_t structure
#define getMaxLengthOfESC_LegacyStatusBits_t() (1)
//! Encode a ESC_LegacyStatusBits_t into a byte array
void encodeESC_LegacyStatusBits_t(uint8_t* data, int* bytecount, const ESC_LegacyStatusBits_t* user);
//! Decode a ESC_LegacyStatusBits_t from a byte array
int decodeESC_LegacyStatusBits_t(const uint8_t* data, int* bytecount, ESC_LegacyStatusBits_t* user);
/*!
* Warning bits associated with the legacy (gen-1) ESC
*/
typedef struct
{
unsigned noRPMSignal : 1; //!< Set if RPM signal is not detected
unsigned overspeed : 1; //!< Set if the ESC motor speed exceeds the configured warning threshold
unsigned overcurrent : 1; //!< Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
unsigned escTemperature : 1; //!< Set if the internal ESC temperature is above the warning threshold
unsigned motorTemperature : 1; //!< Set if the motor temperature is above the warning threshold
unsigned undervoltage : 1; //!< Set if the input voltage is below the minimum threshold
unsigned overvoltage : 1; //!< Set if the input voltage is above the maximum threshold
unsigned invalidPWMsignal : 1; //!< Set if hardware PWM input is enabled but invalid
}ESC_LegacyWarningBits_t;
//! return the minimum encoded length for the ESC_LegacyWarningBits_t structure
#define getMinLengthOfESC_LegacyWarningBits_t() (1)
//! return the maximum encoded length for the ESC_LegacyWarningBits_t structure
#define getMaxLengthOfESC_LegacyWarningBits_t() (1)
//! Encode a ESC_LegacyWarningBits_t into a byte array
void encodeESC_LegacyWarningBits_t(uint8_t* data, int* bytecount, const ESC_LegacyWarningBits_t* user);
//! Decode a ESC_LegacyWarningBits_t from a byte array
int decodeESC_LegacyWarningBits_t(const uint8_t* data, int* bytecount, ESC_LegacyWarningBits_t* user);
/*!
* Error bits associated with the legacy (gen-1) ESC
*/
typedef struct
{
unsigned linkError : 1; //!< Set if communication link to the motor controller is lost
unsigned foldback : 1; //!< Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
unsigned settingsChecksum : 1; //!< Set if the settings checksum does not match the programmed values
unsigned motorSettings : 1; //!< Set if the motor settings are invalid
unsigned reservedD : 1; //!< Reserved for future use
unsigned reservedE : 1; //!< Reserved for future use
unsigned reservedF : 1; //!< Reserved for future use
unsigned reservedG : 1; //!< Reserved for future use
}ESC_LegacyErrorBits_t;
//! return the minimum encoded length for the ESC_LegacyErrorBits_t structure
#define getMinLengthOfESC_LegacyErrorBits_t() (1)
//! return the maximum encoded length for the ESC_LegacyErrorBits_t structure
#define getMaxLengthOfESC_LegacyErrorBits_t() (1)
//! Encode a ESC_LegacyErrorBits_t into a byte array
void encodeESC_LegacyErrorBits_t(uint8_t* data, int* bytecount, const ESC_LegacyErrorBits_t* user);
//! Decode a ESC_LegacyErrorBits_t from a byte array
int decodeESC_LegacyErrorBits_t(const uint8_t* data, int* bytecount, ESC_LegacyErrorBits_t* user);
#ifdef __cplusplus
}
#endif
#endif // _LEGACYESCDEFINES_H

View File

@ -0,0 +1,124 @@
// LegacyESCPackets.c was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#include "LegacyESCPackets.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Create the ESC_LegacyStatusA packet
*
* Legacy (gen-1) definition for the STATUS_A packet
* \param _pg_pkt points to the packet which will be created by this function
* \param mode is ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
* \param status is ESC status bits
* \param warnings is ESC warning bits
* \param errors is ESC *error* bits
* \param command is ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
* \param rpm is Motor speed
*/
void encodeESC_LegacyStatusAPacket(void* _pg_pkt, uint8_t mode, const ESC_LegacyStatusBits_t* status, const ESC_LegacyWarningBits_t* warnings, const ESC_LegacyErrorBits_t* errors, uint16_t command, uint16_t rpm)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Set to 0 to indicate a Gen-2 ESC
_pg_data[_pg_byteindex] = 0;
// ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
// Range of mode is 0 to 127.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(mode, 127);
_pg_byteindex += 1; // close bit field
// ESC status bits
encodeESC_LegacyStatusBits_t(_pg_data, &_pg_byteindex, status);
// ESC warning bits
encodeESC_LegacyWarningBits_t(_pg_data, &_pg_byteindex, warnings);
// ESC *error* bits
encodeESC_LegacyErrorBits_t(_pg_data, &_pg_byteindex, errors);
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
// Range of command is 0 to 65535.
uint16ToBeBytes(command, _pg_data, &_pg_byteindex);
// Motor speed
// Range of rpm is 0 to 65535.
uint16ToBeBytes(rpm, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_LegacyStatusAPacketID());
}// encodeESC_LegacyStatusAPacket
/*!
* \brief Decode the ESC_LegacyStatusA packet
*
* Legacy (gen-1) definition for the STATUS_A packet
* \param _pg_pkt points to the packet being decoded by this function
* \param mode receives ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
* \param status receives ESC status bits
* \param warnings receives ESC warning bits
* \param errors receives ESC *error* bits
* \param command receives ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
* \param rpm receives Motor speed
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_LegacyStatusAPacket(const void* _pg_pkt, uint8_t* mode, ESC_LegacyStatusBits_t* status, ESC_LegacyWarningBits_t* warnings, ESC_LegacyErrorBits_t* errors, uint16_t* command, uint16_t* rpm)
{
unsigned int _pg_tempbitfield = 0;
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_LegacyStatusAPacketID())
return 0;
if(_pg_numbytes < getESC_LegacyStatusAMinDataLength())
return 0;
// Set to 0 to indicate a Gen-2 ESC
_pg_tempbitfield = (_pg_data[_pg_byteindex] >> 7);
// Decoded value must be 0
if(_pg_tempbitfield != 0)
return 0;
// ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
// Range of mode is 0 to 127.
(*mode) = ((_pg_data[_pg_byteindex]) & 0x7F);
_pg_byteindex += 1; // close bit field
// ESC status bits
if(decodeESC_LegacyStatusBits_t(_pg_data, &_pg_byteindex, status) == 0)
return 0;
// ESC warning bits
if(decodeESC_LegacyWarningBits_t(_pg_data, &_pg_byteindex, warnings) == 0)
return 0;
// ESC *error* bits
if(decodeESC_LegacyErrorBits_t(_pg_data, &_pg_byteindex, errors) == 0)
return 0;
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
// Range of command is 0 to 65535.
(*command) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Motor speed
// Range of rpm is 0 to 65535.
(*rpm) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_LegacyStatusAPacket
// end of LegacyESCPackets.c

View File

@ -0,0 +1,57 @@
// LegacyESCPackets.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _LEGACYESCPACKETS_H
#define _LEGACYESCPACKETS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
#include "LegacyESCDefines.h"
/*!
* Legacy (gen-1) definition for the STATUS_A packet
*/
typedef struct
{
uint8_t mode; //!< ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
ESC_LegacyStatusBits_t status; //!< ESC status bits
ESC_LegacyWarningBits_t warnings; //!< ESC warning bits
ESC_LegacyErrorBits_t errors; //!< ESC *error* bits
uint16_t command; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
}ESC_LegacyStatusA_t;
//! Create the ESC_LegacyStatusA packet from parameters
void encodeESC_LegacyStatusAPacket(void* pkt, uint8_t mode, const ESC_LegacyStatusBits_t* status, const ESC_LegacyWarningBits_t* warnings, const ESC_LegacyErrorBits_t* errors, uint16_t command, uint16_t rpm);
//! Decode the ESC_LegacyStatusA packet to parameters
int decodeESC_LegacyStatusAPacket(const void* pkt, uint8_t* mode, ESC_LegacyStatusBits_t* status, ESC_LegacyWarningBits_t* warnings, ESC_LegacyErrorBits_t* errors, uint16_t* command, uint16_t* rpm);
//! return the packet ID for the ESC_LegacyStatusA packet
#define getESC_LegacyStatusAPacketID() (PKT_ESC_STATUS_A)
//! return the minimum encoded length for the ESC_LegacyStatusA packet
#define getESC_LegacyStatusAMinDataLength() (8)
//! return the maximum encoded length for the ESC_LegacyStatusA packet
#define getESC_LegacyStatusAMaxDataLength() (8)
#ifdef __cplusplus
}
#endif
#endif // _LEGACYESCPACKETS_H

View File

@ -1,8 +1,14 @@
// fielddecode.c was generated by ProtoGen version 2.18.c
// fielddecode.c was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#include "fielddecode.h"
/*!
* Decode a null terminated string from a byte stream
* \param string receives the deocded null-terminated string.
@ -115,7 +121,6 @@ float float32FromBeBytes(const uint8_t* bytes, int* index)
return field.floatValue;
}
/*!
* Decode a 4 byte float from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -136,7 +141,6 @@ float float32FromLeBytes(const uint8_t* bytes, int* index)
return field.floatValue;
}
/*!
* Decode a unsigned 4 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -161,7 +165,6 @@ uint32_t uint32FromBeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a unsigned 4 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -186,7 +189,6 @@ uint32_t uint32FromLeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a signed 4 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -211,7 +213,6 @@ int32_t int32FromBeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a signed 4 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -236,7 +237,6 @@ int32_t int32FromLeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a unsigned 3 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -260,7 +260,6 @@ uint32_t uint24FromBeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a unsigned 3 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -284,7 +283,6 @@ uint32_t uint24FromLeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a signed 3 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -311,7 +309,6 @@ int32_t int24FromBeBytes(const uint8_t* bytes, int* index)
return (number ^ m) - m;
}
/*!
* Decode a signed 3 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -338,7 +335,6 @@ int32_t int24FromLeBytes(const uint8_t* bytes, int* index)
return (number ^ m) - m;
}
/*!
* Decode a unsigned 2 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -361,7 +357,6 @@ uint16_t uint16FromBeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a unsigned 2 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -384,7 +379,6 @@ uint16_t uint16FromLeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a signed 2 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -407,7 +401,6 @@ int16_t int16FromBeBytes(const uint8_t* bytes, int* index)
return number;
}
/*!
* Decode a signed 2 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
@ -430,5 +423,4 @@ int16_t int16FromLeBytes(const uint8_t* bytes, int* index)
return number;
}
// end of fielddecode.c

View File

@ -1,9 +1,16 @@
// fielddecode.h was generated by ProtoGen version 2.18.c
// fielddecode.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _FIELDDECODE_H
#define _FIELDDECODE_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
@ -11,41 +18,43 @@ extern "C" {
/*!
* \file
* fielddecode provides routines to pull numbers from a byte stream.
*
* fielddecode provides routines to pull numbers in local memory layout from
* a big or little endian byte stream. It is the opposite operation from the
*
* fielddecode provides routines to pull numbers in local memory layout from a
* big or little endian byte stream. It is the opposite operation from the
* routines contained in fieldencode.h
*
*
* When compressing unsigned numbers (for example 32-bits to 16-bits) the most
* signficant bytes are discarded and the only requirement is that the value of
* the number fits in the smaller width. When going the other direction the
* most significant bytes are simply set to 0x00. However signed two's
* complement numbers are more complicated.
*
*
* If the signed value is a positive number that fits in the range then the
* most significant byte will be zero, and we can discard it. If the signed
* value is negative (in two's complement) then the most significant bytes are
* 0xFF and again we can throw them away. See the example below
*
* 32-bit +100 | 16-bit +100 | 8-bit +100
* 0x00000064 | 0x0064 | 0x64 <-- notice most significant bit clear
*
* 32-bit -100 | 16-bit -100 | 8-bit -100
* 0xFFFFFF9C | 0xFF9C | 0x9C <-- notice most significant bit set
*
*
* 32-bit +100 | 16-bit +100 | 8-bit +100 0x00000064 | 0x0064 | 0x64 <-- notice
* most significant bit clear
*
* 32-bit -100 | 16-bit -100 | 8-bit -100 0xFFFFFF9C | 0xFF9C | 0x9C <-- notice
* most significant bit set
*
* The signed complication comes when going the other way. If the number is
* positive setting the most significant bytes to zero is correct. However
* if the number is negative the most significant bytes must be set to 0xFF.
* This is the process of sign-extension. Typically this is handled by the
* compiler. For example if a int16_t is assigned to an int32_t the compiler
* (or the processor instruction) knows to perform the sign extension. However
* in our case we can decode signed 24-bit numbers (for example) which are
* returned to the caller as int32_t. In this instance fielddecode performs the
* sign extension.
* positive setting the most significant bytes to zero is correct. However if
* the number is negative the most significant bytes must be set to 0xFF. This
* is the process of sign-extension. Typically this is handled by the compiler.
* For example if a int16_t is assigned to an int32_t the compiler (or the
* processor instruction) knows to perform the sign extension. However in our
* case we can decode signed 24-bit numbers (for example) which are returned to
* the caller as int32_t. In this instance fielddecode performs the sign
* extension.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
#include <stdbool.h>
//! Decode a null terminated string from a byte stream
void stringFromBytes(char* string, const uint8_t* bytes, int* index, int maxLength, int fixedLength);
@ -107,4 +116,4 @@ int16_t int16FromLeBytes(const uint8_t* bytes, int* index);
#ifdef __cplusplus
}
#endif
#endif
#endif // _FIELDDECODE_H

View File

@ -1,20 +1,42 @@
// fieldencode.c was generated by ProtoGen version 2.18.c
// fieldencode.c was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#include "fieldencode.h"
/*!
* Copy a null terminated string to a destination whose maximum length (with
* null terminator) is `maxLength`. The destination string is guaranteed to
* have a null terminator when this operation is complete. This is a
* replacement for strncpy().
* \param dst receives the string, and is guaranteed to be null terminated.
* \param src is the null terminated source string to copy.
* \param maxLength is the size of the `dst` buffer.
*/
void pgstrncpy(char* dst, const char* src, int maxLength)
{
int index = 0;
stringToBytes(src, (uint8_t*)dst, &index, maxLength, 0);
}
/*!
* Encode a null terminated string on a byte stream
* \param string is the null termianted string to encode
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by the number of bytes encoded when this function
* is complete.
* \param maxLength is the maximum number of bytes that can be encoded. A null
* terminator is always included in the encoding.
* \param fixedLength should be 1 to force the number of bytes encoded to be
* exactly equal to maxLength.
*/
* Encode a null terminated string on a byte stream
* \param string is the null termianted string to encode
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by the number of bytes encoded when this function
* is complete.
* \param maxLength is the maximum number of bytes that can be encoded. A null
* terminator is always included in the encoding.
* \param fixedLength should be 1 to force the number of bytes encoded to be
* exactly equal to maxLength.
*/
void stringToBytes(const char* string, uint8_t* bytes, int* index, int maxLength, int fixedLength)
{
int i;
@ -121,7 +143,6 @@ void float32ToBeBytes(float number, uint8_t* bytes, int* index)
uint32ToBeBytes(field.integerValue, bytes, index);
}
/*!
* Encode a 4 byte float on a little endian byte stream.
* \param number is the value to encode.
@ -142,7 +163,6 @@ void float32ToLeBytes(float number, uint8_t* bytes, int* index)
uint32ToLeBytes(field.integerValue, bytes, index);
}
/*!
* Encode a unsigned 4 byte integer on a big endian byte stream.
* \param number is the value to encode.
@ -166,7 +186,6 @@ void uint32ToBeBytes(uint32_t number, uint8_t* bytes, int* index)
(*index) += 4;
}
/*!
* Encode a unsigned 4 byte integer on a little endian byte stream.
* \param number is the value to encode.
@ -190,7 +209,6 @@ void uint32ToLeBytes(uint32_t number, uint8_t* bytes, int* index)
(*index) += 4;
}
/*!
* Encode a signed 4 byte integer on a big endian byte stream.
* \param number is the value to encode.
@ -214,7 +232,6 @@ void int32ToBeBytes(int32_t number, uint8_t* bytes, int* index)
(*index) += 4;
}
/*!
* Encode a signed 4 byte integer on a little endian byte stream.
* \param number is the value to encode.
@ -238,7 +255,6 @@ void int32ToLeBytes(int32_t number, uint8_t* bytes, int* index)
(*index) += 4;
}
/*!
* Encode a unsigned 3 byte integer on a big endian byte stream.
* \param number is the value to encode.
@ -260,7 +276,6 @@ void uint24ToBeBytes(uint32_t number, uint8_t* bytes, int* index)
(*index) += 3;
}
/*!
* Encode a unsigned 3 byte integer on a little endian byte stream.
* \param number is the value to encode.
@ -282,7 +297,6 @@ void uint24ToLeBytes(uint32_t number, uint8_t* bytes, int* index)
(*index) += 3;
}
/*!
* Encode a signed 3 byte integer on a big endian byte stream.
* \param number is the value to encode.
@ -304,7 +318,6 @@ void int24ToBeBytes(int32_t number, uint8_t* bytes, int* index)
(*index) += 3;
}
/*!
* Encode a signed 3 byte integer on a little endian byte stream.
* \param number is the value to encode.
@ -326,7 +339,6 @@ void int24ToLeBytes(int32_t number, uint8_t* bytes, int* index)
(*index) += 3;
}
/*!
* Encode a unsigned 2 byte integer on a big endian byte stream.
* \param number is the value to encode.
@ -346,7 +358,6 @@ void uint16ToBeBytes(uint16_t number, uint8_t* bytes, int* index)
(*index) += 2;
}
/*!
* Encode a unsigned 2 byte integer on a little endian byte stream.
* \param number is the value to encode.
@ -366,7 +377,6 @@ void uint16ToLeBytes(uint16_t number, uint8_t* bytes, int* index)
(*index) += 2;
}
/*!
* Encode a signed 2 byte integer on a big endian byte stream.
* \param number is the value to encode.
@ -386,7 +396,6 @@ void int16ToBeBytes(int16_t number, uint8_t* bytes, int* index)
(*index) += 2;
}
/*!
* Encode a signed 2 byte integer on a little endian byte stream.
* \param number is the value to encode.
@ -406,5 +415,4 @@ void int16ToLeBytes(int16_t number, uint8_t* bytes, int* index)
(*index) += 2;
}
// end of fieldencode.c

View File

@ -1,9 +1,16 @@
// fieldencode.h was generated by ProtoGen version 2.18.c
// fieldencode.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _FIELDENCODE_H
#define _FIELDENCODE_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
@ -11,17 +18,17 @@ extern "C" {
/*!
* \file
* fieldencode provides routines to place numbers into a byte stream.
*
* fieldencode provides routines to place numbers in local memory layout into
* a big or little endian byte stream. The byte stream is simply a sequence of
*
* fieldencode provides routines to place numbers in local memory layout into a
* big or little endian byte stream. The byte stream is simply a sequence of
* bytes, as might come from the data payload of a packet.
*
* Support is included for non-standard types such as unsigned 24. When
* working with nonstandard types the data in memory are given using the next
* larger standard type. For example an unsigned 24 is actually a uint32_t in
* which the most significant byte is clear, and only the least significant
* three bytes are placed into a byte stream
*
*
* Support is included for non-standard types such as unsigned 24. When working
* with nonstandard types the data in memory are given using the next larger
* standard type. For example an unsigned 24 is actually a uint32_t in which
* the most significant byte is clear, and only the least significant three
* bytes are placed into a byte stream
*
* Big or Little Endian refers to the order that a computer architecture will
* place the bytes of a multi-byte word into successive memory locations. For
* example the 32-bit number 0x01020304 can be placed in successive memory
@ -31,19 +38,33 @@ extern "C" {
* opened. The choice of name is made to emphasize the degree to which the
* choice of memory layout is un-interesting, as long as one stays within the
* local memory.
*
*
* When transmitting data from one computer to another that assumption no
* longer holds. In computer-to-computer transmission there are three endians
* to consider: the endianness of the sender, the receiver, and the protocol
* between them. A protocol is Big Endian if it sends the most significant
* byte first and the least significant last. If the computer and the protocol
* have the same endianness then encoding data from memory into a byte stream
* is a simple copy. However if the endianness is not the same then bytes must
* be re-ordered for the data to be interpreted correctly.
* between them. A protocol is Big Endian if it sends the most significant byte
* first and the least significant last. If the computer and the protocol have
* the same endianness then encoding data from memory into a byte stream is a
* simple copy. However if the endianness is not the same then bytes must be
* re-ordered for the data to be interpreted correctly.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
#include <stdbool.h>
//! Macro to limit a number to be no more than a maximum value
#define limitMax(number, max) (((number) > (max)) ? (max) : (number))
//! Macro to limit a number to be no less than a minimum value
#define limitMin(number, min) (((number) < (min)) ? (min) : (number))
//! Macro to limit a number to be no less than a minimum value and no more than a maximum value
#define limitBoth(number, min, max) (((number) > (max)) ? (max) : (limitMin((number), (min))))
//! Copy a null terminated string
void pgstrncpy(char* dst, const char* src, int maxLength);
//! Encode a null terminated string on a byte stream
void stringToBytes(const char* string, uint8_t* bytes, int* index, int maxLength, int fixedLength);
@ -105,4 +126,4 @@ void int16ToLeBytes(int16_t number, uint8_t* bytes, int* index);
#ifdef __cplusplus
}
#endif
#endif
#endif // _FIELDENCODE_H

View File

@ -1,15 +0,0 @@
/*
This program 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 program 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/>.
*/

View File

@ -1,278 +0,0 @@
<?xml version="1.0"?>
<!--
This file provides the CAN protocol definition for the "ESC Velocity" speed controller manufactured by Currawong Engineering: https://www.currawongeng.com/servos-escs/esc-velocity/
-->
<Protocol name="ESCVelocity" prefix="ESC_" api="23" version="3.05" endian="big" supportSpecialFloat="false" supportInt64="false" supportFloat64="false" comment=
"This is the ICD for the Currawong Engineering Electronic Speed Controller (ESCVelocity). This document details the ESCVelocity command and packet structure for communication with and configuration of the ESC">
<Include name="string.h" comment="C string manipulation function header" global="true"/>
<Documentation name="Global ESC Enumerations" paragraph="1" comment="Packets in the protocol refer to these global enumerations."/>
<!-- TOP LEVEL ENUMERATIONS -->
<Enum name="ESCDisableSequence" comment="ESC_Disable_Sequence">
<Value name="ESC_DISABLE_A" value="0xAA" comment="Constant value required for disabling the ESC"/>
<Value name="ESC_DISABLE_B" value="0xC3" comment="Constant value required for disabling the ESC"/>
</Enum>
<Enum name="ESCEnableSequence" comment="ESC_Enable_Sequence">
<Value name="ESC_ENABLE_A" value="0xAA" comment="Constant value required for enabling the ESC"/>
<Value name="ESC_ENABLE_B" value="0x3C" comment="Constant value required for enabling the ESC"/>
</Enum>
<Enum name="ESCOperatingModes" prefix="ESC_MODE_" lookup="true" comment="ESC Operational Modes" description="These values define the various modes of operation of the ESC">
<Value name="STANDBY" value="0x00" comment="ESC is in standby mode - the motor is OFF but the ESC is ready to accept motor commands"/>
<Value name="PWM" comment="ESC is controlling motor in open-loop mode based on a 'PWM' (Pulse Width) input"/>
<Value name="RPM" comment="ESC is controlling motor speed based on an RPM setpoint"/>
<Value name="ESC_VALID_MODES" ignorePrefix="true" comment="ESC mode counter"/>
</Enum>
<Enum name="ESCCommandSources" prefix="ESC_COMMAND_SOURCE_" lookup="true" comment="ESC Command Sources" description="These values define the source that the ESC has received its most recent valid command from">
<Value name="NONE" value="0x00" comment="No valid command has been received"/>
<Value name="CAN" comment="Most recent command from CAN"/>
<Value name="PWM" comment="Most recent command from PWM"/>
</Enum>
<Enum name="ESCMotorTemperatureSensor" prefix="ESC_MOTOR_TEMP_SENSOR_" lookup="true" comment="ESC motor temperature sensor options">
<Value name="OFF" value="0x00" comment="No temperature sensor selected"/>
<Value name="KTY84" comment="KTY84 of equivalent"/>
<Value name="KTY83" comment="KTY83 or equivalent"/>
</Enum>
<Enum name="ESCCommandPriorities" prefix="ESC_COMMAND_PRIORITY_" lookup="true" comment="ESC Command Priorities">
<Value name="CAN_ONLY" value="0x00" comment="Commands only from CAN, PWM hardware input is disabled"/>
<Value name="CAN_PRIORITY" comment="Commands from CAN or PWM hardware input, CAN takes priority"/>
<Value name="PWM_PRIORITY" comment="Commands from CAN or PWM hardware input, PWM takes priority"/>
</Enum>
<Enum name="ESCMotorDirections" prefix="ESC_MOTOR_DIR_" comment="Motor Direction Enumeration">
<Value name="FORWARD" value="0x00" comment="Forward motor direction"/>
<Value name="REVERSE" value="0x01" comment="Reverse motor direction"/>
</Enum>
<Enum name="ESCBeepModes" prefix="ESC_BEEP_" comment="Motor beep modes enumeration">
<Value name="NONE" value="0b00"/>
<Value name="STATUS" value="0b01" comment="Motor status beeps only"/>
<Value name="ERROR" value="0b10" comment="Motor error beeps only"/>
<Value name="ALL" value="0b11" comment="All motor beeps"/>
</Enum>
<Documentation name="Packet IDs" paragraph="1" comment="Packet type definitions. Each packet has an 8-bit packet identifier (ID) which is used to identify the contents of the packet"/>
<Enum name="ESCMultiCommandPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Multi Command Packets" description="These packets can be used to send commands to 4 (four) ESCs with sequential CAN address identifiers, using a single CAN message. When sending these messages, they must be broadcast (using the special ESC broadcast address) so that each of the four target ESCs accept the CAN message.">
<Value name="SETPOINT_1" value ="0" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 1 - 4"/>
<Value name="SETPOINT_2" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 5 - 8"/>
<Value name="SETPOINT_3" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 9 - 12"/>
<Value name="SETPOINT_4" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 13 - 16"/>
<Value name="SETPOINT_5" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 17 - 20"/>
<Value name="SETPOINT_6" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 21 - 24"/>
<Value name="SETPOINT_7" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 25 - 28"/>
<Value name="SETPOINT_8" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 29 - 32"/>
<Value name="SETPOINT_9" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 33 - 36"/>
<Value name="SETPOINT_10" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 37 - 40"/>
<Value name="SETPOINT_11" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 41 - 44"/>
<Value name="SETPOINT_12" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 45 - 48"/>
<Value name="SETPOINT_13" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 49 - 52"/>
<Value name="SETPOINT_14" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 53 - 56"/>
<Value name="SETPOINT_15" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 57 - 60"/>
<Value name="SETPOINT_16" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 61 - 64"/>
</Enum>
<Enum name="ESCCommandPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Command Packets" description="Command packets are sent to the ESC to change its operational mode. These packets **must** be fully implemented in the connected avionics system for complete operation of the PCU">
<Value name="PWM_CMD" value="0x10" comment="Send a PWM (Pulse width) command to a particular ESC"/>
<Value name="RPM_CMD" comment="Send an RPM (Speed) command to a particular ESC"/>
<Value name="DISABLE" value="0x20" comment="Send this packet to an ESC to disable the ESC"/>
<Value name="STANDBY" comment="Send this packet to an ESC to enable the ESC and place it in Standby mode"/>
</Enum>
<Enum name="ESCStatusPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Status Packets" description="Status packets are transmitted by the ESC at (user-configurable) intervals. These packets contain vital system information and should be fully implemented by the connected avionics device(s).">
<!-- Telemetry Packets -->
<Value name="STATUS_A" value="0x80" comment="ESC Status A telemetry packet transmitted by the ESC at regular intervals"/>
<Value name="STATUS_B" comment="ESC Status B telemetry packet transmitted by the ESC at regular intervals"/>
<Value name="ACCELEROMETER" value="0x88" comment="Raw accelerometer data"/>
</Enum>
<Enum name="ESCPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Packets Definitions" description="ESC configuration packets. Each packet can be requested from the ESC by sending a zero-length packet of the same type.">
<!-- System information / settings packets -->
<Value name="SERIAL_NUMBER" value="0x90" comment="ESC Serial Number and User ID information"/>
<Value name="TITLE" comment="Human-readable string descriptor (max 8 chars) of the particular ESC"/>
<Value name="FIRMWARE" comment="ESC Firmware information"/>
<Value name="SYSTEM_INFO" comment="ESC system information packet"/>
<Value name="TELEMETRY_SETTINGS" comment="Telemetry packet configuration"/>
<Value name="EEPROM" comment="ESC non-volatile data information and settings"/>
</Enum>
<!-- ESC Status Bitfield -->
<Structure name="StatusBits" file="ESCDefines" comment="The *status* of the ESC is represented using these status bits. ESC system functionality can be quickly determined using these bits">
<Data name="hwInhibit" inMemoryType="bitfield1" comment="1 = Hardware inhibit is active (ESC is disabled)"/>
<Data name="swInhibit" inMemoryType="bitfield1" comment="1 = Software inhibit is active (ESC is disabled)"/>
<Data name="afwEnabled" inMemoryType="bitfield1" comment="0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled"/>
<Data name="direction" inMemoryType="bitfield1" comment="0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE"/>
<Data name="timeout" inMemoryType="bitfield1" comment="Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)"/>
<Data name="starting" inMemoryType="bitfield1" comment="1 = in starting mode (0 = stopped or running)"/>
<Data name="commandSource" inMemoryType="bitfield1" comment="0 = most recent command from CAN, 1 = most recent command from PWM"/>
<Data name="running" inMemoryType="bitfield1" comment="ESC is running"/>
</Structure>
<Structure name="WarningBits" file="ESCDefines" comment="The *warning* bits enumerate various system warnings/errors of which the user (or user software) should be made aware. These *warning* bits are transmitted in the telemetry packets such that user software is aware of any these *warning* conditions and can poll the ESC for particular packets if any further information is needed. The ESC will continue to function in the case of a *warning* state">
<Data name="noRPMSignal" inMemoryType="bitfield1" comment="Set if RPM signal is not detected"/>
<Data name="overspeed" inMemoryType="bitfield1" comment="Set if the ESC motor speed exceeds the configured warning threshold"/>
<Data name="overcurrent" inMemoryType="bitfield1" comment="Set if the ESC motor current (positive or negative) exceeds the configured warning threshold"/>
<Data name="escTemperature" inMemoryType="bitfield1" comment="Set if the internal ESC temperature is above the warning threshold"/>
<Data name="motorTemperature" inMemoryType="bitfield1" comment="Set if the motor temperature is above the warning threshold"/>
<Data name="undervoltage" inMemoryType="bitfield1" comment="Set if the input voltage is below the minimum threshold"/>
<Data name="overvoltage" inMemoryType="bitfield1" comment="Set if the input voltage is above the maximum threshold"/>
<Data name="invalidPWMsignal" inMemoryType="bitfield1" comment="Set if hardware PWM input is enabled but invalid"/>
</Structure>
<Structure name="ErrorBits" file="ESCDefines" comment="The *error* bits enumerate critical system errors that will cause the ESC to stop functioning until the error cases are alleviated">
<Data name="linkError" inMemoryType="bitfield1" comment="Set if communication link to the motor controller is lost"/>
<Data name="foldback" inMemoryType="bitfield1" comment="Set if the ESC has detected an overcurrent event and is actively folding back duty cycle"/>
<Data name="settingsChecksum" inMemoryType="bitfield1" comment="Set if the settings checksum does not match the programmed values"/>
<Data name="motorSettings" inMemoryType="bitfield1" comment="Set if the motor settings are invalid"/>
<Data name="reservedD" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="reservedE" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="reservedF" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="reservedG" inMemoryType="bitfield1" comment="Reserved for future use"/>
</Structure>
<!-- Non-Volatile Settings Information -->
<Structure name="TelemetryPackets" file="ESCDefines" comment="These bits are used to determine which packets are automatically transmitted as telemetry data by the ESC. Only the packets described here can be configured as telemetry packets">
<Data name="statusA" inMemoryType="bitfield1" initialValue="1" comment="If this bit is set, the STATUS_A packet will be transmitted at the configured rate"/>
<Data name="statusB" inMemoryType="bitfield1" initialValue="1" comment="If this bit is set, the STATUS_B packet will be transmitted at the configured rate"/>
<Data name="statusC" inMemoryType="bitfield1" initialValue="1" comment="If this bit is set, the STATUS_C packet will be transmitted at the configured rate"/>
<Data name="accelerometer" inMemoryType="bitfield1" initialValue="0" comment="If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate"/>
<Data name="statusD" inMemoryType="bitfield1" comment="If this bit is set, the STATUS_D packet will be transmitted at the configured rate"/>
<Data name="reservedB" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="piccoloDownlink" inMemoryType="bitfield1" comment="If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)"/>
<Data name="reservedD" inMemoryType="bitfield1" comment="Reserved for future use"/>
</Structure>
<!-- Command Packet Definitions Start Here -->
<Documentation name="Command Packets" paragraph="1" comment="These packets are sent to the ESC to command certain operational modes. The ESC does not acknowledge these packets"/>
<Packet name="CommandMultipleESCs"
ID="PKT_ESC_SETPOINT_1 PKT_ESC_SETPOINT_2 PKT_ESC_SETPOINT_3 PKT_ESC_SETPOINT_4 PKT_ESC_SETPOINT_5 PKT_ESC_SETPOINT_6"
file="ESCPackets" parameterInterface="true" comment="Send this packet to command ESCs which have CAN ID values in the range {1,4} (inclusive). This packet must be sent as a broadcast packet (address = 0xFF) such that all ESCs can receive it. Similiar commands are available for commanding ESCs with ID values up to 64, using different ESC_SETPOINT_x packet ID values.">
<Data name="pwmValueA" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 1" units="1us per bit"/>
<Data name="pwmValueB" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 2" units="1us per bit"/>
<Data name="pwmValueC" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 3" units="1us per bit"/>
<Data name="pwmValueD" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 4" units="1us per bit"/>
</Packet>
<Packet name="Disable" ID="PKT_ESC_DISABLE" file="ESCPackets" parameterInterface="true" comment="Send this packet to the ESC to disable it. The ESC will not accept PWM/RPM commands until it is re-enabled.">
<Data name="disableSequenceA" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_DISABLE_A" comment="This value must be set for the command to be accepted"/>
<Data name="disableSequenceB" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_DISABLE_B" comment="This value must be set for the command to be accepted"/>
</Packet>
<Packet name="Enable" ID="PKT_ESC_STANDBY" file="ESCPackets" parameterInterface="true" comment="Send this packet to the ESC to enable it. The ESC will be placed in Standby mode.">
<Data name="enableSequenceA" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_ENABLE_A" comment="This value must be set for the command to be accepted"/>
<Data name="enableSequenceB" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_ENABLE_B" comment="This value must be set for the command to be included"/>
</Packet>
<Packet name="PWMCommand" ID="PKT_ESC_PWM_CMD" parameterInterface="true" file="ESCPackets" comment="Send a PWM (pulse width) command to an individual ESC. The pulse width value in specified in microseconds for compatibility with standard ESC interface. Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus.">
<Data name="pwmCommand" inMemoryType="unsigned16" comment="PWM command" units="1us per bit"/>
</Packet>
<Packet name="RPMCommand" ID="PKT_ESC_RPM_CMD" parameterInterface="true" file="ESCPackets" comment="Send an RPM (speed) command to an individual ESC. Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus">
<Data name="rpmCommand" inMemoryType="unsigned16" comment="RPM Command" units="RPM"/>
</Packet>
<!--
STATUS PACKETS
-->
<Documentation name="Status Packets" paragraph="1" comment="These packets are transmitted by the ESC at a user-configurable rate. These packets contain operational data pertaining to the status of the ESC. Each packet can also be requested (polled) by sending a zero-length packet of the same type."/>
<Packet name="StatusA" ID="PKT_ESC_STATUS_A" file="ESCPackets" parameterInterface="true" structureInterface="true"
comment="The ESC_STATUS_A packet contains high-priority ESC status information. This packet is transmitted by the ESC at regular (user-configurable) intervals. It can also be requested (polled) from the ESC by sending a zero-length packet of the same type.">
<Data name="mode" inMemoryType="unsigned8" comment="ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use."/>
<Data name="status" struct="StatusBits" comment="ESC status bits"/>
<Data name="warnings" struct="WarningBits" comment="ESC warning bits"/>
<Data name="errors" struct="ErrorBits" comment="ESC *error* bits"/>
<Data name="command" inMemoryType="unsigned16" comment="ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM"/>
<Data name="rpm" inMemoryType="unsigned16" comment="Motor speed" units="1RPM per bit"/>
</Packet>
<Packet name="StatusB" ID="PKT_ESC_STATUS_B" file="ESCPackets" parameterInterface="true" structureInterface="true"
comment="The ESC_STATUS_B packet contains ESC operational information. This packet is transmitted by the ESC at regular (user-configurable) intervals. It can also be requested (polled) from the ESC by sending a zero-length packet of the same type.">
<Data name="voltage" inMemoryType="unsigned16" comment="ESC Rail Voltage" units="0.1V per bit"/>
<Data name="current" inMemoryType="signed16" units="0.1A per bit" comment="ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative"/>
<Data name="dutyCycle" inMemoryType="unsigned16" comment="ESC Motor Duty Cycle" units="0.1% per bit"/>
<Data name="escTemperature" inMemoryType="signed8" comment="ESC Board Temperature" units="1 degree C per bit" range="-128C to +127C"/>
<Data name="motorTemperature" inMemoryType="unsigned8" comment="ESC Motor Temperature" units="1 degree C per bit" range="-50 to +205 (0 = -50C)"/>
</Packet>
<Packet name="Accelerometer" ID="PKT_ESC_ACCELEROMETER" parameterInterface="true" structureInterface="true" file="ESCPackets"
comment="This packet contains raw accelerometer data from the ESC. It can be requested (polled) from the ESC by sending a zero-length packet of the same type. It can also be transmitted by the ESC at high-frequency using the high-frequency streaming functionality of the ESC">
<Data name="xAcc" inMemoryType="signed16" comment="X axis acceleration value" range="-0x7FFF to +0x7FFF" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units"/>
<Data name="yAcc" inMemoryType="signed16" comment="Y axis acceleration value" range="-0x7FFF to +0x7FFF" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units"/>
<Data name="zAcc" inMemoryType="signed16" comment="Z axis acceleration value" range="-0x7FFF to +0x7FFF" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units"/>
<Data name="fullscale" inMemoryType="unsigned8" comment="Accelerometer full-scale range"/>
<Data name="resolution" inMemoryType="unsigned8" comment="Accelerometer measurement resolution, in 'bits'."/>
</Packet>
<!-- System info / settings packets -->
<Documentation name="Config Packets" paragraph="1" comment="These packets provide information on the ESC system status, and allow the avionics device and/or operator to determine that the ESC is correctly configured prior to flight. To request these config packets, send a zero-length packet with the same ID to the ESC. Note: For complete ESC configuration use the cEQUIP software provided by Currawong Engineering"/>
<Packet name="Address" ID="PKT_ESC_SERIAL_NUMBER" file="ESCPackets" structureInterface="true" parameterInterface="true" comment="This packet contains the serial number for the ESC. Additionally there are two extra values (each 16-bit) which can be programmed by the user for any purpose.">
<!-- The serial number was previously transmitted at 32-bit (but we are overriding the top byte to be hardware revision)
For backwards compatibility, the first byte in the packet must be used so the packet definitions are not corrupted. -->
<Data name="HardwareRevision" inMemoryType="unsigned8" comment="ESC hardware revision"/>
<Data name="SerialNumber" inMemoryType="unsigned32" encodedType="unsigned24" comment="ESC Serial Number (OTP - not configurable by user)"/>
<Data name="UserIDA" inMemoryType="unsigned16" comment="User ID Value A - user can set this value to any value"/>
<Data name="UserIDB" inMemoryType="unsigned16" comment="User ID Value B - user can set this value to any value"/>
</Packet>
<Packet name="Title" ID="PKT_ESC_TITLE" file="ESCPackets" parameterInterface="true" comment="This packet contains a zero-terminated string (max-length 8) used to identify the particular ESC.">
<Data name="ESCTitle" inMemoryType="unsigned8" array="8" comment="Description of this ESC"/>
</Packet>
<Packet name="Firmware" ID="PKT_ESC_FIRMWARE" file="ESCPackets" structureInterface="true" parameterInterface="true"
comment="This packet contains the firmware version of the ESC">
<Data name="versionMajor" inMemoryType="unsigned8" comment="Major firmware version number"/>
<Data name="versionMinor" inMemoryType="unsigned8" comment="Minor firmware version numner"/>
<Data name="versionDay" inMemoryType="unsigned8" comment="Firmware release date, day-of-month" range="1-31"/>
<Data name="versionMonth" inMemoryType="unsigned8" comment="Firmware release data, month-of-year" range="1-12"/>
<Data name="versionYear" inMemoryType="unsigned16" comment="Firmware release date, year"/>
<Data name="firmwareChecksum" inMemoryType="unsigned16" comment="Firmware checksum"/>
</Packet>
<Packet name="SystemInfo" ID="PKT_ESC_SYSTEM_INFO" file="ESCPackets" structureInterface="true" parameterInterface="true"
comment="This packet contains system runtime information">
<Data name="millisecondsSinceReset" inMemoryType="unsigned32" comment="Number of milliseconds since the ESC last experienced a reset/power-on event"/>
<Data name="powerCycles" inMemoryType="unsigned16" comment="Number of power cycle events that the ESC has experienced"/>
<Data name="resetCode" inMemoryType="unsigned8" comment="Processor RESET code for debug purposes"/>
<Data name="cpuOccupancy" inMemoryType="unsigned8" comment="Processor usage" units="1% per bit"/>
</Packet>
<Packet name="TelemetryConfig" ID="PKT_ESC_TELEMETRY_SETTINGS" useInOtherPackets="true" file="ESCPackets" structureInterface="true" parameterInterface="true" comment="Telemetry settings (storage class)" hidden="true">
<Data name="period" inMemoryType="unsigned8" comment="Telemetry period" units="50ms per bit" range="0 - 250 (0.0s to 25.0s)" initialValue="4" verifyMaxValue="250" notes="0 = Telemetry disabled"/>
<Data name="silence" inMemoryType="unsigned8" comment="Telemetry silence period (delay after RESET before telemetry data is sent)" units="50ms per bit" initialValue="20" verifyMaxValue="250" range="0 - 250 (0.0s to 25.0s)"/>
<Data name="packets" struct="TelemetryPackets" comment="Bitfield describing which telemetry packets are enabled"/>
</Packet>
<Packet name="TelemetrySettings" ID="PKT_ESC_TELEMETRY_SETTINGS" file="ESCPackets" parameterInterface="true" comment="This packet contains the telemetry packet configuration">
<Data name="settings" struct="TelemetryConfig" comment="Telemetry settings"/>
<Data name="apiVersion" inMemoryType="string" array="5" constant="getESCVelocityVersion()" comment="The API version of the ESC"/>
</Packet>
<Packet name="EEPROMSettings" ID="PKT_ESC_EEPROM" file="ESCPackets" parameterInterface="true" structureInterface="true"
comment="This packet contains information on the non-volatile ESC settings">
<Data name="version" inMemoryType="unsigned8" comment="Version of EEPROM data"/>
<Data name="size" inMemoryType="unsigned16" comment="Size of settings data"/>
<Data name="checksum" inMemoryType="unsigned16" comment="Settings checksum"/>
</Packet>
</Protocol>

File diff suppressed because it is too large Load Diff

View File

@ -1,69 +1,236 @@
// scaleddecode.h was generated by ProtoGen version 2.18.c
// scaleddecode.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _SCALEDDECODE_H
#define _SCALEDDECODE_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
/*!
* \file
* scaleddecode routines extract scaled numbers from a byte stream.
*
* scaleddecode routines extract scaled numbers from a byte stream. The routines
* in this module are the reverse operation of the routines in scaledencode.
*
* Code generation for this module was affected by these global flags:
* 64-bit integers are not supported.
* Normal bitfields are supported, long bitfields are not.
* Double precision floating points are not supported.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
//! Inverse scale the bitfield base integer type to a float32
//! Compute a float using inverse floating point scaling from the base integer type used for bitfields.
float float32ScaledFromBitfield(unsigned int value, float min, float invscaler);
//! Compute a float scaled from 4 unsigned bytes in big endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 4 unsigned bytes in big endian order.
float float32ScaledFrom4UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 4 unsigned bytes in little endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 4 unsigned bytes in little endian order.
float float32ScaledFrom4UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 4 signed bytes in big endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 4 signed bytes in big endian order.
float float32ScaledFrom4SignedBeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 4 signed bytes in little endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 4 signed bytes in little endian order.
float float32ScaledFrom4SignedLeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 3 unsigned bytes in big endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 3 unsigned bytes in big endian order.
float float32ScaledFrom3UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 3 unsigned bytes in little endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 3 unsigned bytes in little endian order.
float float32ScaledFrom3UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 3 signed bytes in big endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 3 signed bytes in big endian order.
float float32ScaledFrom3SignedBeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 3 signed bytes in little endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 3 signed bytes in little endian order.
float float32ScaledFrom3SignedLeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 2 unsigned bytes in big endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 2 unsigned bytes in big endian order.
float float32ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 2 unsigned bytes in little endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 2 unsigned bytes in little endian order.
float float32ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 2 signed bytes in big endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 2 signed bytes in big endian order.
float float32ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 2 signed bytes in little endian order.
//! Decode a float from a byte stream by inverse floating point scaling from 2 signed bytes in little endian order.
float float32ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 1 unsigned byte.
//! Decode a float from a byte stream by inverse floating point scaling from 1 unsigned byte.
float float32ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 1 signed byte.
//! Decode a float from a byte stream by inverse floating point scaling from 1 signed byte.
float float32ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a uint32_t using inverse integer scaling from the base integer type used for bitfields.
uint32_t uint32ScaledFromBitfield(unsigned int value, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 4 unsigned bytes in big endian order.
uint32_t uint32ScaledFrom4UnsignedBeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 4 unsigned bytes in little endian order.
uint32_t uint32ScaledFrom4UnsignedLeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 4 signed bytes in big endian order.
uint32_t uint32ScaledFrom4SignedBeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 4 signed bytes in little endian order.
uint32_t uint32ScaledFrom4SignedLeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 3 unsigned bytes in big endian order.
uint32_t uint32ScaledFrom3UnsignedBeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 3 unsigned bytes in little endian order.
uint32_t uint32ScaledFrom3UnsignedLeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 3 signed bytes in big endian order.
uint32_t uint32ScaledFrom3SignedBeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 3 signed bytes in little endian order.
uint32_t uint32ScaledFrom3SignedLeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 2 unsigned bytes in big endian order.
uint32_t uint32ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 2 unsigned bytes in little endian order.
uint32_t uint32ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 2 signed bytes in big endian order.
uint32_t uint32ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 2 signed bytes in little endian order.
uint32_t uint32ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 1 unsigned byte.
uint32_t uint32ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a uint32_t from a byte stream by inverse integer scaling from 1 signed byte.
uint32_t uint32ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Compute a int32_t using inverse integer scaling from the base integer type used for bitfields.
int32_t int32ScaledFromBitfield(unsigned int value, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 4 unsigned bytes in big endian order.
int32_t int32ScaledFrom4UnsignedBeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 4 unsigned bytes in little endian order.
int32_t int32ScaledFrom4UnsignedLeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 4 signed bytes in big endian order.
int32_t int32ScaledFrom4SignedBeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 4 signed bytes in little endian order.
int32_t int32ScaledFrom4SignedLeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 3 unsigned bytes in big endian order.
int32_t int32ScaledFrom3UnsignedBeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 3 unsigned bytes in little endian order.
int32_t int32ScaledFrom3UnsignedLeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 3 signed bytes in big endian order.
int32_t int32ScaledFrom3SignedBeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 3 signed bytes in little endian order.
int32_t int32ScaledFrom3SignedLeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 2 unsigned bytes in big endian order.
int32_t int32ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 2 unsigned bytes in little endian order.
int32_t int32ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 2 signed bytes in big endian order.
int32_t int32ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 2 signed bytes in little endian order.
int32_t int32ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 1 unsigned byte.
int32_t int32ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, int32_t min, uint32_t divisor);
//! Decode a int32_t from a byte stream by inverse integer scaling from 1 signed byte.
int32_t int32ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, uint32_t divisor);
//! Compute a uint16_t using inverse integer scaling from the base integer type used for bitfields.
uint16_t uint16ScaledFromBitfield(unsigned int value, int16_t min, uint16_t divisor);
//! Decode a uint16_t from a byte stream by inverse integer scaling from 2 unsigned bytes in big endian order.
uint16_t uint16ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, int16_t min, uint16_t divisor);
//! Decode a uint16_t from a byte stream by inverse integer scaling from 2 unsigned bytes in little endian order.
uint16_t uint16ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, int16_t min, uint16_t divisor);
//! Decode a uint16_t from a byte stream by inverse integer scaling from 2 signed bytes in big endian order.
uint16_t uint16ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, uint16_t divisor);
//! Decode a uint16_t from a byte stream by inverse integer scaling from 2 signed bytes in little endian order.
uint16_t uint16ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, uint16_t divisor);
//! Decode a uint16_t from a byte stream by inverse integer scaling from 1 unsigned byte.
uint16_t uint16ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, int16_t min, uint16_t divisor);
//! Decode a uint16_t from a byte stream by inverse integer scaling from 1 signed byte.
uint16_t uint16ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, uint16_t divisor);
//! Compute a int16_t using inverse integer scaling from the base integer type used for bitfields.
int16_t int16ScaledFromBitfield(unsigned int value, int16_t min, uint16_t divisor);
//! Decode a int16_t from a byte stream by inverse integer scaling from 2 unsigned bytes in big endian order.
int16_t int16ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, int16_t min, uint16_t divisor);
//! Decode a int16_t from a byte stream by inverse integer scaling from 2 unsigned bytes in little endian order.
int16_t int16ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, int16_t min, uint16_t divisor);
//! Decode a int16_t from a byte stream by inverse integer scaling from 2 signed bytes in big endian order.
int16_t int16ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, uint16_t divisor);
//! Decode a int16_t from a byte stream by inverse integer scaling from 2 signed bytes in little endian order.
int16_t int16ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, uint16_t divisor);
//! Decode a int16_t from a byte stream by inverse integer scaling from 1 unsigned byte.
int16_t int16ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, int16_t min, uint16_t divisor);
//! Decode a int16_t from a byte stream by inverse integer scaling from 1 signed byte.
int16_t int16ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, uint16_t divisor);
//! Compute a uint8_t using inverse integer scaling from the base integer type used for bitfields.
uint8_t uint8ScaledFromBitfield(unsigned int value, int8_t min, uint8_t divisor);
//! Decode a uint8_t from a byte stream by inverse integer scaling from 1 unsigned byte.
uint8_t uint8ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, int8_t min, uint8_t divisor);
//! Decode a uint8_t from a byte stream by inverse integer scaling from 1 signed byte.
uint8_t uint8ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, uint8_t divisor);
//! Compute a int8_t using inverse integer scaling from the base integer type used for bitfields.
int8_t int8ScaledFromBitfield(unsigned int value, int8_t min, uint8_t divisor);
//! Decode a int8_t from a byte stream by inverse integer scaling from 1 unsigned byte.
int8_t int8ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, int8_t min, uint8_t divisor);
//! Decode a int8_t from a byte stream by inverse integer scaling from 1 signed byte.
int8_t int8ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, uint8_t divisor);
#ifdef __cplusplus
}
#endif
#endif
#endif // _SCALEDDECODE_H

File diff suppressed because it is too large Load Diff

View File

@ -1,13 +1,24 @@
// scaledencode.h was generated by ProtoGen version 2.18.c
// scaledencode.h was generated by ProtoGen version 3.2.a
/*
* Copyright Currawong Engineering Pty Ltd
* www.currawongeng.com
* all rights reserved
*/
#ifndef _SCALEDENCODE_H
#define _SCALEDENCODE_H
// C++ compilers: don't mangle us
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
/*!
* \file
* scaledencode routines place scaled numbers into a byte stream.
@ -25,7 +36,7 @@ extern "C" {
* per second and encode it in two bytes from -200 to 200 meters per second.
* In that example the encoding function would be:
*
* floatScaledTo2SignedBeBytes(speed, bytestream, &index, 200);
* float32ScaledTo2SignedBeBytes(speed, bytestream, &index, 200);
*
* This would scale the speed according to (32767/200), and copy the resulting
* two bytes to bytestream[index] as a signed 16 bit number in big endian
@ -34,7 +45,7 @@ extern "C" {
* Another example encoding is: take a double that represents altitude in
* meters and encode it in three bytes from -1000 to 49000 meters:
*
* doubleScaledTo3UnsignedLeBytes(alt, bytestream, &index, -1000, 49000);
* float64ScaledTo3UnsignedLeBytes(alt, bytestream, &index, -1000, 49000);
*
* This would transform the altitude according to (alt *(16777215/50000) + 1000)
* and copy the resulting three bytes to bytestream[index] as an unsigned 24
@ -42,61 +53,216 @@ extern "C" {
* resolution of 0.003 meters.
*
* scaledencode does not include routines that increase the resolution of the
* source value. For example the function floatScaledTo5UnsignedBeBytes() does
* inmemory value. For example the function floatScaledTo5UnsignedBeBytes() does
* not exist, because expanding a float to 5 bytes does not make any resolution
* improvement over encoding it in 4 bytes. In general the encoded format
* must be equal to or less than the number of bytes of the raw data.
*
* Code generation for this module was affected by these global flags:
* 64-bit integers are not supported.
* Normal bitfields are supported, long bitfields are not.
* Double precision floating points are not supported.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
//! Scale a float32 to the base integer type used for bitfield
unsigned int float32ScaledToBitfield(float value, float min, float scaler);
//! Scale a float using floating point scaling to the base integer type used for bitfields.
unsigned int float32ScaledToBitfield(float value, float min, float scaler, int bits);
//! Encode a float on a byte stream by scaling to fit in 4 unsigned bytes in big endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 4 unsigned bytes in big endian order.
void float32ScaledTo4UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 unsigned bytes in little endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 4 unsigned bytes in little endian order.
void float32ScaledTo4UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 signed bytes in big endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 4 signed bytes in big endian order.
void float32ScaledTo4SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 signed bytes in little endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 4 signed bytes in little endian order.
void float32ScaledTo4SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 unsigned bytes in big endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 3 unsigned bytes in big endian order.
void float32ScaledTo3UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 unsigned bytes in little endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 3 unsigned bytes in little endian order.
void float32ScaledTo3UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 signed bytes in big endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 3 signed bytes in big endian order.
void float32ScaledTo3SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 signed bytes in little endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 3 signed bytes in little endian order.
void float32ScaledTo3SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 unsigned bytes in big endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 2 unsigned bytes in big endian order.
void float32ScaledTo2UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 unsigned bytes in little endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 2 unsigned bytes in little endian order.
void float32ScaledTo2UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 signed bytes in big endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 2 signed bytes in big endian order.
void float32ScaledTo2SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 signed bytes in little endian order.
//! Encode a float on a byte stream by floating point scaling to fit in 2 signed bytes in little endian order.
void float32ScaledTo2SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 1 unsigned byte.
//! Encode a float on a byte stream by floating point scaling to fit in 1 unsigned byte.
void float32ScaledTo1UnsignedBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 1 signed byte.
//! Encode a float on a byte stream by floating point scaling to fit in 1 signed byte.
void float32ScaledTo1SignedBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Scale a uint32_t using integer scaling to the base integer type used for bitfields.
unsigned int uint32ScaledToBitfield(uint32_t value, int32_t min, uint32_t scaler, int bits);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 4 unsigned bytes in big endian order.
void uint32ScaledTo4UnsignedBeBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 4 unsigned bytes in little endian order.
void uint32ScaledTo4UnsignedLeBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 4 signed bytes in big endian order.
void uint32ScaledTo4SignedBeBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 4 signed bytes in little endian order.
void uint32ScaledTo4SignedLeBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 3 unsigned bytes in big endian order.
void uint32ScaledTo3UnsignedBeBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 3 unsigned bytes in little endian order.
void uint32ScaledTo3UnsignedLeBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 3 signed bytes in big endian order.
void uint32ScaledTo3SignedBeBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 3 signed bytes in little endian order.
void uint32ScaledTo3SignedLeBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 2 unsigned bytes in big endian order.
void uint32ScaledTo2UnsignedBeBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 2 unsigned bytes in little endian order.
void uint32ScaledTo2UnsignedLeBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 2 signed bytes in big endian order.
void uint32ScaledTo2SignedBeBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 2 signed bytes in little endian order.
void uint32ScaledTo2SignedLeBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 1 unsigned byte.
void uint32ScaledTo1UnsignedBytes(uint32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a uint32_t on a byte stream by integer scaling to fit in 1 signed byte.
void uint32ScaledTo1SignedBytes(uint32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Scale a int32_t using integer scaling to the base integer type used for bitfields.
unsigned int int32ScaledToBitfield(int32_t value, int32_t min, uint32_t scaler, int bits);
//! Encode a int32_t on a byte stream by integer scaling to fit in 4 unsigned bytes in big endian order.
void int32ScaledTo4UnsignedBeBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 4 unsigned bytes in little endian order.
void int32ScaledTo4UnsignedLeBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 4 signed bytes in big endian order.
void int32ScaledTo4SignedBeBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 4 signed bytes in little endian order.
void int32ScaledTo4SignedLeBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 3 unsigned bytes in big endian order.
void int32ScaledTo3UnsignedBeBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 3 unsigned bytes in little endian order.
void int32ScaledTo3UnsignedLeBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 3 signed bytes in big endian order.
void int32ScaledTo3SignedBeBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 3 signed bytes in little endian order.
void int32ScaledTo3SignedLeBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 2 unsigned bytes in big endian order.
void int32ScaledTo2UnsignedBeBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 2 unsigned bytes in little endian order.
void int32ScaledTo2UnsignedLeBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 2 signed bytes in big endian order.
void int32ScaledTo2SignedBeBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 2 signed bytes in little endian order.
void int32ScaledTo2SignedLeBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 1 unsigned byte.
void int32ScaledTo1UnsignedBytes(int32_t value, uint8_t* bytes, int* index, int32_t min, uint32_t scaler);
//! Encode a int32_t on a byte stream by integer scaling to fit in 1 signed byte.
void int32ScaledTo1SignedBytes(int32_t value, uint8_t* bytes, int* index, uint32_t scaler);
//! Scale a uint16_t using integer scaling to the base integer type used for bitfields.
unsigned int uint16ScaledToBitfield(uint16_t value, int16_t min, uint16_t scaler, int bits);
//! Encode a uint16_t on a byte stream by integer scaling to fit in 2 unsigned bytes in big endian order.
void uint16ScaledTo2UnsignedBeBytes(uint16_t value, uint8_t* bytes, int* index, int16_t min, uint16_t scaler);
//! Encode a uint16_t on a byte stream by integer scaling to fit in 2 unsigned bytes in little endian order.
void uint16ScaledTo2UnsignedLeBytes(uint16_t value, uint8_t* bytes, int* index, int16_t min, uint16_t scaler);
//! Encode a uint16_t on a byte stream by integer scaling to fit in 2 signed bytes in big endian order.
void uint16ScaledTo2SignedBeBytes(uint16_t value, uint8_t* bytes, int* index, uint16_t scaler);
//! Encode a uint16_t on a byte stream by integer scaling to fit in 2 signed bytes in little endian order.
void uint16ScaledTo2SignedLeBytes(uint16_t value, uint8_t* bytes, int* index, uint16_t scaler);
//! Encode a uint16_t on a byte stream by integer scaling to fit in 1 unsigned byte.
void uint16ScaledTo1UnsignedBytes(uint16_t value, uint8_t* bytes, int* index, int16_t min, uint16_t scaler);
//! Encode a uint16_t on a byte stream by integer scaling to fit in 1 signed byte.
void uint16ScaledTo1SignedBytes(uint16_t value, uint8_t* bytes, int* index, uint16_t scaler);
//! Scale a int16_t using integer scaling to the base integer type used for bitfields.
unsigned int int16ScaledToBitfield(int16_t value, int16_t min, uint16_t scaler, int bits);
//! Encode a int16_t on a byte stream by integer scaling to fit in 2 unsigned bytes in big endian order.
void int16ScaledTo2UnsignedBeBytes(int16_t value, uint8_t* bytes, int* index, int16_t min, uint16_t scaler);
//! Encode a int16_t on a byte stream by integer scaling to fit in 2 unsigned bytes in little endian order.
void int16ScaledTo2UnsignedLeBytes(int16_t value, uint8_t* bytes, int* index, int16_t min, uint16_t scaler);
//! Encode a int16_t on a byte stream by integer scaling to fit in 2 signed bytes in big endian order.
void int16ScaledTo2SignedBeBytes(int16_t value, uint8_t* bytes, int* index, uint16_t scaler);
//! Encode a int16_t on a byte stream by integer scaling to fit in 2 signed bytes in little endian order.
void int16ScaledTo2SignedLeBytes(int16_t value, uint8_t* bytes, int* index, uint16_t scaler);
//! Encode a int16_t on a byte stream by integer scaling to fit in 1 unsigned byte.
void int16ScaledTo1UnsignedBytes(int16_t value, uint8_t* bytes, int* index, int16_t min, uint16_t scaler);
//! Encode a int16_t on a byte stream by integer scaling to fit in 1 signed byte.
void int16ScaledTo1SignedBytes(int16_t value, uint8_t* bytes, int* index, uint16_t scaler);
//! Scale a uint8_t using integer scaling to the base integer type used for bitfields.
unsigned int uint8ScaledToBitfield(uint8_t value, int8_t min, uint8_t scaler, int bits);
//! Encode a uint8_t on a byte stream by integer scaling to fit in 1 unsigned byte.
void uint8ScaledTo1UnsignedBytes(uint8_t value, uint8_t* bytes, int* index, int8_t min, uint8_t scaler);
//! Encode a uint8_t on a byte stream by integer scaling to fit in 1 signed byte.
void uint8ScaledTo1SignedBytes(uint8_t value, uint8_t* bytes, int* index, uint8_t scaler);
//! Scale a int8_t using integer scaling to the base integer type used for bitfields.
unsigned int int8ScaledToBitfield(int8_t value, int8_t min, uint8_t scaler, int bits);
//! Encode a int8_t on a byte stream by integer scaling to fit in 1 unsigned byte.
void int8ScaledTo1UnsignedBytes(int8_t value, uint8_t* bytes, int* index, int8_t min, uint8_t scaler);
//! Encode a int8_t on a byte stream by integer scaling to fit in 1 signed byte.
void int8ScaledTo1SignedBytes(int8_t value, uint8_t* bytes, int* index, uint8_t scaler);
#ifdef __cplusplus
}
#endif
#endif
#endif // _SCALEDENCODE_H