ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/ESCPackets.h

1018 lines
45 KiB
C

// ESCPackets.h was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ESCPACKETS_H
#define _ESCPACKETS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdint.h>
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
#include "ESCDefines.h"
typedef struct
{
unsigned reserved : 2;
unsigned polarity : 3;
}ESC_HallSensorPattern_t;
//! return the minimum encoded length for the ESC_HallSensorPattern_t structure
#define getMinLengthOfESC_HallSensorPattern_t() (1)
//! return the maximum encoded length for the ESC_HallSensorPattern_t structure
#define getMaxLengthOfESC_HallSensorPattern_t() (1)
//! Encode a ESC_HallSensorPattern_t into a byte array
void encodeESC_HallSensorPattern_t(uint8_t* data, int* bytecount, const ESC_HallSensorPattern_t* user);
//! Decode a ESC_HallSensorPattern_t from a byte array
int decodeESC_HallSensorPattern_t(const uint8_t* data, int* bytecount, ESC_HallSensorPattern_t* user);
/*!
* RPM control loop settings
*/
typedef struct
{
ESC_ControlLoopCommon_t pid; //!< Core control loop settings
uint16_t rpmRateLimit; //!< RPM setpoint rate limit
float rpmFilter; //!< Corner frequency for RPM measurement LPF
}ESC_RPMControlLoopSettings_t;
//! Create the ESC_RPMControlLoopSettings packet
void encodeESC_RPMControlLoopSettingsPacketStructure(void* pkt, const ESC_RPMControlLoopSettings_t* user);
//! Decode the ESC_RPMControlLoopSettings packet
int decodeESC_RPMControlLoopSettingsPacketStructure(const void* pkt, ESC_RPMControlLoopSettings_t* user);
//! Encode a ESC_RPMControlLoopSettings_t into a byte array
void encodeESC_RPMControlLoopSettings_t(uint8_t* data, int* bytecount, const ESC_RPMControlLoopSettings_t* user);
//! Decode a ESC_RPMControlLoopSettings_t from a byte array
int decodeESC_RPMControlLoopSettings_t(const uint8_t* data, int* bytecount, ESC_RPMControlLoopSettings_t* user);
//! return the packet ID for the ESC_RPMControlLoopSettings packet
#define getESC_RPMControlLoopSettingsPacketID() (PKT_ESC_RPM_LOOP_SETTINGS)
//! return the minimum encoded length for the ESC_RPMControlLoopSettings packet
#define getESC_RPMControlLoopSettingsMinDataLength() (8)
//! return the maximum encoded length for the ESC_RPMControlLoopSettings packet
#define getESC_RPMControlLoopSettingsMaxDataLength() (15)
/*!
* 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
bool enablePwmInput; //!< 1 = Digital PWM input is enabled
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 disableLED; //!< 1 = Disable LED
uint8_t canBitRate; //!< CAN bit (baud) rate
uint8_t canProtocol; //!< Protocol to communicate over CAN
bool motorBraking; //!< Enable motor brake strength (applied when motor is off)
uint8_t swInhibitDelay; //!< Delay between hardware inhibit and software inhibit events
uint8_t motorBeepMode; //!< Sets the motor beep mode for the ESC
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, bool enablePwmInput, uint8_t motorTempSensor, uint8_t keepalive, uint8_t disableLED, uint8_t canBitRate, uint8_t canProtocol, bool motorBraking, uint8_t swInhibitDelay, 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, bool* enablePwmInput, uint8_t* motorTempSensor, uint8_t* keepalive, uint8_t* disableLED, uint8_t* canBitRate, uint8_t* canProtocol, bool* motorBraking, uint8_t* swInhibitDelay, 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 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;
//! 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 from parameters
void encodeESC_TelemetryConfigPacket(void* pkt, uint8_t period, uint8_t silence, const ESC_TelemetryPackets_t* packets);
//! 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)
//! return the minimum encoded length for the ESC_TelemetryConfig packet
#define getESC_TelemetryConfigMinDataLength() (3)
//! return the maximum encoded length for the ESC_TelemetryConfig packet
#define getESC_TelemetryConfigMaxDataLength() (3)
/*!
* This packet can be used to simultaneously command multiple ESCs which have
* sequential CAN ID values. This packet must be sent as a broadcast packet
* (address = 0xFF) such that all ESCs can receive it. These commands can be
* sent to groups of ESCs with ID values up to 64, using different
* ESC_SETPOINT_x packet ID values.
*/
typedef struct
{
uint16_t pwmValueA; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 1]
uint16_t pwmValueB; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 2]
uint16_t pwmValueC; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 3]
uint16_t pwmValueD; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 4]
}ESC_CommandMultipleESCs_t;
//! 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 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
#define getESC_CommandMultipleESCsMinDataLength() (8)
//! return the maximum encoded length for the ESC_CommandMultipleESCs packet
#define getESC_CommandMultipleESCsMaxDataLength() (8)
//! Create the ESC_Disable packet from parameters
void encodeESC_DisablePacket(void* pkt);
//! Decode the ESC_Disable packet to parameters
int decodeESC_DisablePacket(const void* pkt);
//! return the packet ID for the ESC_Disable packet
#define getESC_DisablePacketID() (PKT_ESC_DISABLE)
//! return the minimum encoded length for the ESC_Disable packet
#define getESC_DisableMinDataLength() (2)
//! return the maximum encoded length for the ESC_Disable packet
#define getESC_DisableMaxDataLength() (2)
//! Create the ESC_Enable packet from parameters
void encodeESC_EnablePacket(void* pkt);
//! Decode the ESC_Enable packet to parameters
int decodeESC_EnablePacket(const void* pkt);
//! return the packet ID for the ESC_Enable packet
#define getESC_EnablePacketID() (PKT_ESC_STANDBY)
//! return the minimum encoded length for the ESC_Enable packet
#define getESC_EnableMinDataLength() (2)
//! return the maximum encoded length for the ESC_Enable packet
#define getESC_EnableMaxDataLength() (2)
//! Create the ESC_PWMCommand packet from parameters
void encodeESC_PWMCommandPacket(void* pkt, uint16_t pwmCommand);
//! 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
#define getESC_PWMCommandPacketID() (PKT_ESC_PWM_CMD)
//! return the minimum encoded length for the ESC_PWMCommand packet
#define getESC_PWMCommandMinDataLength() (2)
//! return the maximum encoded length for the ESC_PWMCommand packet
#define getESC_PWMCommandMaxDataLength() (2)
//! Create the ESC_RPMCommand packet from parameters
void encodeESC_RPMCommandPacket(void* pkt, uint16_t rpmCommand);
//! 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
#define getESC_RPMCommandPacketID() (PKT_ESC_RPM_CMD)
//! return the minimum encoded length for the ESC_RPMCommand packet
#define getESC_RPMCommandMinDataLength() (2)
//! return the maximum encoded length for the ESC_RPMCommand packet
#define getESC_RPMCommandMaxDataLength() (2)
//! Create the ESC_VoltageCommand packet from parameters
void encodeESC_VoltageCommandPacket(void* pkt, uint16_t voltageCommand);
//! Decode the ESC_VoltageCommand packet to parameters
int decodeESC_VoltageCommandPacket(const void* pkt, uint16_t* voltageCommand);
//! return the packet ID for the ESC_VoltageCommand packet
#define getESC_VoltageCommandPacketID() (PKT_ESC_VOLT_CMD)
//! return the minimum encoded length for the ESC_VoltageCommand packet
#define getESC_VoltageCommandMinDataLength() (2)
//! return the maximum encoded length for the ESC_VoltageCommand packet
#define getESC_VoltageCommandMaxDataLength() (2)
/*!
* 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.
*/
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 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);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacketStructure(const void* pkt, 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 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)
//! return the minimum encoded length for the ESC_StatusA packet
#define getESC_StatusAMinDataLength() (8)
//! return the maximum encoded length for the ESC_StatusA packet
#define getESC_StatusAMaxDataLength() (8)
/*!
* 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.
*/
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 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 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 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
#define getESC_StatusBPacketID() (PKT_ESC_STATUS_B)
//! return the minimum encoded length for the ESC_StatusB packet
#define getESC_StatusBMinDataLength() (8)
//! return the maximum encoded length for the ESC_StatusB packet
#define getESC_StatusBMaxDataLength() (8)
/*!
* The ESC_STATUS_C packet contains ESC operational information. This packet is
* transmitted by the ESC at regular intervals (user-configurable). It can also
* be requested (polled) from the ESC by sending a zero-length packet of the
* same type.
*/
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
void encodeESC_StatusCPacketStructure(void* pkt, const ESC_StatusC_t* user);
//! Decode the ESC_StatusC packet
int decodeESC_StatusCPacketStructure(const void* pkt, ESC_StatusC_t* user);
//! 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)
/*!
* The ESC_STATUS_D packet contains ESC operational information. This packet is
* transmitted by the ESC at regular intervals (user-configurable). It can also
* be requested (polled) from the ESC by sending a zero-length packet of the
* same type.
*/
typedef struct
{
uint8_t demagAngle; //!< Measured demag angle of motor
}ESC_StatusD_t;
//! Create the ESC_StatusD packet
void encodeESC_StatusDPacketStructure(void* pkt, const ESC_StatusD_t* user);
//! Decode the ESC_StatusD packet
int decodeESC_StatusDPacketStructure(const void* pkt, ESC_StatusD_t* user);
//! Create the ESC_StatusD packet from parameters
void encodeESC_StatusDPacket(void* pkt, uint8_t demagAngle);
//! Decode the ESC_StatusD packet to parameters
int decodeESC_StatusDPacket(const void* pkt, uint8_t* demagAngle);
//! return the packet ID for the ESC_StatusD packet
#define getESC_StatusDPacketID() (PKT_ESC_STATUS_D)
//! return the minimum encoded length for the ESC_StatusD packet
#define getESC_StatusDMinDataLength() (8)
//! return the maximum encoded length for the ESC_StatusD packet
#define getESC_StatusDMaxDataLength() (8)
/*!
* Warning and error status information. If any warning or error flags are set,
* this packet is transmitted by the ESC at 10Hz. If there are no warning or
* error flags set, the packet is transmitted by the ESC at 1Hz.
*/
typedef struct
{
ESC_WarningBits_t warnings; //!< ESC warning bitfield
ESC_ErrorBits_t errors; //!< ESC error bitfield
uint8_t extended; //!< Set to indicate that this packet contains extended warning and error information
ESC_WarningBits_t warningsExtended; //!< Extension of ESC warning bitfield
ESC_ErrorBits_t errorsExtended; //!< Extension of ESC error bifield
}ESC_WarningErrorStatus_t;
//! Create the ESC_WarningErrorStatus packet from parameters
void encodeESC_WarningErrorStatusPacket(void* pkt, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors, uint8_t extended, const ESC_WarningBits_t* warningsExtended, const ESC_ErrorBits_t* errorsExtended);
//! Decode the ESC_WarningErrorStatus packet to parameters
int decodeESC_WarningErrorStatusPacket(const void* pkt, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors, uint8_t* extended, ESC_WarningBits_t* warningsExtended, ESC_ErrorBits_t* errorsExtended);
//! 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() (8)
/*!
* This packet contains the current output values for the RPM controller.
*/
typedef struct
{
float pTerm;
float iTerm;
float fTerm;
int16_t output; //!< Output duty cycle
}ESC_ControlLoopOutputs_t;
//! Create the ESC_ControlLoopOutputs packet
void encodeESC_ControlLoopOutputsPacketStructure(void* pkt, const ESC_ControlLoopOutputs_t* user);
//! Decode the ESC_ControlLoopOutputs packet
int decodeESC_ControlLoopOutputsPacketStructure(const void* pkt, ESC_ControlLoopOutputs_t* user);
//! Create the ESC_ControlLoopOutputs packet from parameters
void encodeESC_ControlLoopOutputsPacket(void* pkt, float pTerm, float iTerm, float fTerm, int16_t output);
//! Decode the ESC_ControlLoopOutputs packet to parameters
int decodeESC_ControlLoopOutputsPacket(const void* pkt, float* pTerm, float* iTerm, float* fTerm, int16_t* output);
//! return the packet ID for the ESC_ControlLoopOutputs packet
#define getESC_ControlLoopOutputsPacketID() (PKT_ESC_CONTROL_LOOP_DATA)
//! return the minimum encoded length for the ESC_ControlLoopOutputs packet
#define getESC_ControlLoopOutputsMinDataLength() (8)
//! return the maximum encoded length for the ESC_ControlLoopOutputs packet
#define getESC_ControlLoopOutputsMaxDataLength() (8)
/*!
* This packet contains information on the hall sensor
*/
typedef struct
{
ESC_HallSensorPattern_t detectedPattern;
}ESC_HallSensorInfo_t;
//! Create the ESC_HallSensorInfo packet from parameters
void encodeESC_HallSensorInfoPacket(void* pkt, const ESC_HallSensorPattern_t* detectedPattern);
//! Decode the ESC_HallSensorInfo packet to parameters
int decodeESC_HallSensorInfoPacket(const void* pkt, ESC_HallSensorPattern_t* detectedPattern);
//! return the packet ID for the ESC_HallSensorInfo packet
#define getESC_HallSensorInfoPacketID() (PKT_ESC_HALL_SENSOR_INFO)
//! return the minimum encoded length for the ESC_HallSensorInfo packet
#define getESC_HallSensorInfoMinDataLength() (1)
//! return the maximum encoded length for the ESC_HallSensorInfo packet
#define getESC_HallSensorInfoMaxDataLength() (1)
/*!
* Motor status flags. If any warning or error flags are set, this packet is
* transmitted by the ESC at 10Hz. If there are no warning or error flags set,
* the packet is transmitted by the ESC at 1Hz.
*/
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)
/*!
* Voltage control loop settings
*/
typedef struct
{
ESC_ControlLoopCommon_t pid; //!< Core control loop settings
}ESC_VoltageControlLoopSettings_t;
//! Create the ESC_VoltageControlLoopSettings packet
void encodeESC_VoltageControlLoopSettingsPacketStructure(void* pkt, const ESC_VoltageControlLoopSettings_t* user);
//! Decode the ESC_VoltageControlLoopSettings packet
int decodeESC_VoltageControlLoopSettingsPacketStructure(const void* pkt, ESC_VoltageControlLoopSettings_t* user);
//! Create the ESC_VoltageControlLoopSettings packet from parameters
void encodeESC_VoltageControlLoopSettingsPacket(void* pkt, const ESC_ControlLoopCommon_t* pid);
//! Decode the ESC_VoltageControlLoopSettings packet to parameters
int decodeESC_VoltageControlLoopSettingsPacket(const void* pkt, ESC_ControlLoopCommon_t* pid);
//! return the packet ID for the ESC_VoltageControlLoopSettings packet
#define getESC_VoltageControlLoopSettingsPacketID() (PKT_ESC_VOLT_LOOP_SETTINGS)
//! return the minimum encoded length for the ESC_VoltageControlLoopSettings packet
#define getESC_VoltageControlLoopSettingsMinDataLength() (8)
//! return the maximum encoded length for the ESC_VoltageControlLoopSettings packet
#define getESC_VoltageControlLoopSettingsMaxDataLength() (11)
/*!
* ESC self-protection settings
*/
typedef struct
{
float overcurrentBus; //!< Maximum allowable DC bus current
float overcurrentPhase; //!< Maximum allowable motor phase current
float overcurrentRegen; //!< Maximum allowable regen current
uint8_t overtemperatureInternal; //!< Maximum allowable internal temperature
uint8_t overtemperatureMotor; //!< Maximum allowable motor temperature
uint16_t overspeed; //!< Maximum motor speed
uint8_t undervoltage; //!< ESC undervoltage warning threshold
uint8_t overvoltage; //!< ESC overvoltage warning threshold
uint8_t demagAngle; //!< Maximum allowable demag angle
uint8_t timingAdvance; //!< Maximum allowable timing advance
}ESC_ProtectionValues_t;
//! Create the ESC_ProtectionValues packet
void encodeESC_ProtectionValuesPacketStructure(void* pkt, const ESC_ProtectionValues_t* user);
//! Decode the ESC_ProtectionValues packet
int decodeESC_ProtectionValuesPacketStructure(const void* pkt, ESC_ProtectionValues_t* user);
//! Create the ESC_ProtectionValues packet from parameters
void encodeESC_ProtectionValuesPacket(void* pkt, float overcurrentBus, float overcurrentPhase, float overcurrentRegen, uint8_t overtemperatureInternal, uint8_t overtemperatureMotor, uint16_t overspeed, uint8_t undervoltage, uint8_t overvoltage, uint8_t demagAngle, uint8_t timingAdvance);
//! Decode the ESC_ProtectionValues packet to parameters
int decodeESC_ProtectionValuesPacket(const void* pkt, float* overcurrentBus, float* overcurrentPhase, float* overcurrentRegen, uint8_t* overtemperatureInternal, uint8_t* overtemperatureMotor, uint16_t* overspeed, uint8_t* undervoltage, uint8_t* overvoltage, uint8_t* demagAngle, uint8_t* timingAdvance);
//! return the packet ID for the ESC_ProtectionValues packet
#define getESC_ProtectionValuesPacketID() (PKT_ESC_PROTECTION_LEVELS)
//! return the minimum encoded length for the ESC_ProtectionValues packet
#define getESC_ProtectionValuesMinDataLength() (10)
//! return the maximum encoded length for the ESC_ProtectionValues packet
#define getESC_ProtectionValuesMaxDataLength() (11)
/*!
* ESC protection actions
*/
typedef struct
{
uint8_t overcurrentBus; //!< Action when bus current exceeds limit
uint8_t overcurrentPhase; //!< Action when phase current exceeds limit
uint8_t overcurrentRegen; //!< Action when regen current exceeds limit
uint8_t overtemperatureInternal; //!< Action when ESC temperature exceeds limit
uint8_t overtemperatureMotor; //!< Action when motor temperature exceeds limit
uint8_t overspeed; //!< Action when motor speed exceeds limit
uint8_t undervoltage; //!< Action when DC voltage falls below configured lower limit
uint8_t overvoltage; //!< Action when DC voltage exceeds configured upper limit
uint8_t demagAngle; //!< Action when motor demag angle exceeds limit
uint8_t commutationLoss; //!< Action on motor commutation estimator failure
}ESC_ProtectionActions_t;
//! Create the ESC_ProtectionActions packet
void encodeESC_ProtectionActionsPacketStructure(void* pkt, const ESC_ProtectionActions_t* user);
//! Decode the ESC_ProtectionActions packet
int decodeESC_ProtectionActionsPacketStructure(const void* pkt, ESC_ProtectionActions_t* user);
//! Create the ESC_ProtectionActions packet from parameters
void encodeESC_ProtectionActionsPacket(void* pkt, uint8_t overcurrentBus, uint8_t overcurrentPhase, uint8_t overcurrentRegen, uint8_t overtemperatureInternal, uint8_t overtemperatureMotor, uint8_t overspeed, uint8_t undervoltage, uint8_t overvoltage, uint8_t demagAngle, uint8_t commutationLoss);
//! Decode the ESC_ProtectionActions packet to parameters
int decodeESC_ProtectionActionsPacket(const void* pkt, uint8_t* overcurrentBus, uint8_t* overcurrentPhase, uint8_t* overcurrentRegen, uint8_t* overtemperatureInternal, uint8_t* overtemperatureMotor, uint8_t* overspeed, uint8_t* undervoltage, uint8_t* overvoltage, uint8_t* demagAngle, uint8_t* commutationLoss);
//! return the packet ID for the ESC_ProtectionActions packet
#define getESC_ProtectionActionsPacketID() (PKT_ESC_PROTECTION_ACTIONS)
//! return the minimum encoded length for the ESC_ProtectionActions packet
#define getESC_ProtectionActionsMinDataLength() (3)
//! return the maximum encoded length for the ESC_ProtectionActions packet
#define getESC_ProtectionActionsMaxDataLength() (4)
/*!
* Motor and system parameters
*/
typedef struct
{
uint8_t reserved; //!< Reserved for future packet expansion. Field is encoded constant.
uint16_t motorKv; //!< Motor RPM constant
uint8_t polePairs; //!< Motor pole pairs count
uint16_t maxSpeed; //!< Maximum motor speed
}ESC_MotorParameters_t;
//! Create the ESC_MotorParameters packet
void encodeESC_MotorParametersPacketStructure(void* pkt, const ESC_MotorParameters_t* user);
//! Decode the ESC_MotorParameters packet
int decodeESC_MotorParametersPacketStructure(const void* pkt, ESC_MotorParameters_t* user);
//! return the packet ID for the ESC_MotorParameters packet
#define getESC_MotorParametersPacketID() (PKT_ESC_MOTOR_PARAMETERS)
//! return the minimum encoded length for the ESC_MotorParameters packet
#define getESC_MotorParametersMinDataLength() (4)
//! return the maximum encoded length for the ESC_MotorParameters packet
#define getESC_MotorParametersMaxDataLength() (6)
/*!
* Hall sensor configuration options
*/
typedef struct
{
bool bypassStartingChecks; //!< Bypass extra checks for starting in hall sensor mode
uint8_t mode; //!< Hall sensor operational mode
uint8_t polarity; //!< Hall sensor U/V/W polarity
uint16_t timeout; //!< Time (in milliseconds) for no hall sensor transitions to trigger an error (0 = forever)
uint16_t maxSpeed; //!< Maximum electrical RPM when running under hall sensor control
uint16_t transitionSpeed; //!< RPM threshold for transferring to sensorless motor control
uint8_t transitionHysteresis; //!< RPM hysteresis for switching between sensored and sensorless control
}ESC_MotorHallSensorConfig_t;
//! Create the ESC_MotorHallSensorConfig packet
void encodeESC_MotorHallSensorConfigPacketStructure(void* pkt, const ESC_MotorHallSensorConfig_t* user);
//! Decode the ESC_MotorHallSensorConfig packet
int decodeESC_MotorHallSensorConfigPacketStructure(const void* pkt, ESC_MotorHallSensorConfig_t* user);
//! return the packet ID for the ESC_MotorHallSensorConfig packet
#define getESC_MotorHallSensorConfigPacketID() (PKT_ESC_MOTOR_HALL_CONFIG)
//! return the minimum encoded length for the ESC_MotorHallSensorConfig packet
#define getESC_MotorHallSensorConfigMinDataLength() (9)
//! return the maximum encoded length for the ESC_MotorHallSensorConfig packet
#define getESC_MotorHallSensorConfigMaxDataLength() (9)
/*!
* 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.
*/
typedef struct
{
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;
//! Create the ESC_Address packet
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 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 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)
//! return the minimum encoded length for the ESC_Address packet
#define getESC_AddressMinDataLength() (8)
//! return the maximum encoded length for the ESC_Address packet
#define getESC_AddressMaxDataLength() (8)
/*!
* 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
void encodeESC_TitlePacketStructure(void* pkt, const ESC_Title_t* user);
//! Decode the ESC_Title packet
int decodeESC_TitlePacketStructure(const void* pkt, ESC_Title_t* user);
//! Create the ESC_Title packet from parameters
void encodeESC_TitlePacket(void* pkt, const uint8_t ESCTitle[8]);
//! 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
#define getESC_TitlePacketID() (PKT_ESC_TITLE)
//! return the minimum encoded length for the ESC_Title packet
#define getESC_TitleMinDataLength() (8)
//! return the maximum encoded length for the ESC_Title packet
#define getESC_TitleMaxDataLength() (8)
/*!
* This packet contains the firmware version of the ESC
*/
typedef struct
{
uint8_t versionMajor; //!< Major firmware version number
uint8_t versionMinor; //!< Minor firmware version numner
uint8_t versionDay; //!< Firmware release date, day-of-month
uint8_t versionMonth; //!< Firmware release data, month-of-year
uint16_t versionYear; //!< Firmware release date, year
uint16_t firmwareChecksum; //!< Firmware checksum
}ESC_Firmware_t;
//! Create the ESC_Firmware packet
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 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 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
#define getESC_FirmwarePacketID() (PKT_ESC_FIRMWARE)
//! return the minimum encoded length for the ESC_Firmware packet
#define getESC_FirmwareMinDataLength() (8)
//! return the maximum encoded length for the ESC_Firmware packet
#define getESC_FirmwareMaxDataLength() (8)
/*!
* This packet contains system runtime information
*/
typedef struct
{
uint32_t millisecondsSinceReset; //!< Number of milliseconds since the ESC last experienced a reset/power-on event
uint16_t powerCycles; //!< Number of power cycle events that the ESC has experienced
uint8_t resetCode; //!< Processor RESET code for debug purposes
uint8_t cpuOccupancy; //!< Processor usage
}ESC_SystemInfo_t;
//! Create the ESC_SystemInfo packet
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 from parameters
void encodeESC_SystemInfoPacket(void* pkt, uint32_t millisecondsSinceReset, uint16_t powerCycles, uint8_t resetCode, uint8_t cpuOccupancy);
//! 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
#define getESC_SystemInfoPacketID() (PKT_ESC_SYSTEM_INFO)
//! return the minimum encoded length for the ESC_SystemInfo packet
#define getESC_SystemInfoMinDataLength() (8)
//! return the maximum encoded length for the ESC_SystemInfo packet
#define getESC_SystemInfoMaxDataLength() (8)
/*!
* This packet contains the telemetry packet configuration
*/
typedef struct
{
ESC_TelemetryConfig_t settings; //!< Telemetry settings
char apiVersion[5]; //!< The API version of the ESC. Field is encoded constant.
}ESC_TelemetrySettings_t;
//! Create the ESC_TelemetrySettings packet
void encodeESC_TelemetrySettingsPacketStructure(void* pkt, const ESC_TelemetrySettings_t* user);
//! Decode the ESC_TelemetrySettings packet
int decodeESC_TelemetrySettingsPacketStructure(const void* pkt, ESC_TelemetrySettings_t* user);
//! Create the ESC_TelemetrySettings packet from parameters
void encodeESC_TelemetrySettingsPacket(void* pkt, const ESC_TelemetryConfig_t* settings);
//! 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
#define getESC_TelemetrySettingsPacketID() (PKT_ESC_TELEMETRY_SETTINGS)
//! return the minimum encoded length for the ESC_TelemetrySettings packet
#define getESC_TelemetrySettingsMinDataLength() (4)
//! return the maximum encoded length for the ESC_TelemetrySettings packet
#define getESC_TelemetrySettingsMaxDataLength() (8)
/*!
* This packet contains information on the non-volatile ESC settings
*/
typedef struct
{
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
void encodeESC_EEPROMSettingsPacketStructure(void* pkt, const ESC_EEPROMSettings_t* user);
//! Decode the ESC_EEPROMSettings packet
int decodeESC_EEPROMSettingsPacketStructure(const void* pkt, ESC_EEPROMSettings_t* user);
//! 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 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)
//! return the minimum encoded length for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsMinDataLength() (5)
//! return the maximum encoded length for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsMaxDataLength() (7)
/*!
* Motor temperature sensor settings
*/
typedef struct
{
int16_t NTC_T[3]; //!< Reference temperature values
float NTC_R[3]; //!< Reference resistance values
uint16_t Beta; //!< Beta constant
}ESC_TempSensorConfig_t;
//! Create the ESC_TempSensorConfig packet
void encodeESC_TempSensorConfigPacketStructure(void* pkt, const ESC_TempSensorConfig_t* user);
//! Decode the ESC_TempSensorConfig packet
int decodeESC_TempSensorConfigPacketStructure(const void* pkt, ESC_TempSensorConfig_t* user);
//! Create the ESC_TempSensorConfig packet from parameters
void encodeESC_TempSensorConfigPacket(void* pkt, const int16_t NTC_T[3], const float NTC_R[3], uint16_t Beta);
//! Decode the ESC_TempSensorConfig packet to parameters
int decodeESC_TempSensorConfigPacket(const void* pkt, int16_t NTC_T[3], float NTC_R[3], uint16_t* Beta);
//! return the packet ID for the ESC_TempSensorConfig packet
#define getESC_TempSensorConfigPacketID() (PKT_ESC_MOTOR_TEMP_SENSOR)
//! return the minimum encoded length for the ESC_TempSensorConfig packet
#define getESC_TempSensorConfigMinDataLength() (20)
//! return the maximum encoded length for the ESC_TempSensorConfig packet
#define getESC_TempSensorConfigMaxDataLength() (20)
/*!
* ESC telltale values
*/
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
void encodeESC_GitHashPacketStructure(void* pkt, const ESC_GitHash_t* user);
//! Decode the ESC_GitHash packet
int decodeESC_GitHashPacketStructure(const void* pkt, ESC_GitHash_t* user);
//! 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
{
bool glitchFilter; //!< Enable median glitch filter for PWM input
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, bool glitchFilter, 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, bool* glitchFilter, 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 // _ESCPACKETS_H