ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/ESCVelocity_source.xml

606 lines
56 KiB
XML

<Protocol api="62" 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.41"><Include comment="C string manipulation function header" global="true" name="string.h" />
<Structure comment="Status bits associated with the legacy (gen-1) ESC" file="LegacyESCDefines" name="LegacyStatusBits">
<Data comment="1 = Hardware inhibit is active (ESC is disabled)" inMemoryType="bitfield1" name="hwInhibit" />
<Data comment="1 = Software inhibit is active (ESC is disabled)" inMemoryType="bitfield1" name="swInhibit" />
<Data comment="0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled" inMemoryType="bitfield1" name="afwEnabled" />
<Data comment="0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE" inMemoryType="bitfield1" name="direction" />
<Data comment="Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)" inMemoryType="bitfield1" name="timeout" />
<Data comment="1 = in starting mode (0 = stopped or running)" inMemoryType="bitfield1" name="starting" />
<Data comment="0 = most recent command from CAN, 1 = most recent command from PWM" inMemoryType="bitfield1" name="commandSource" />
<Data comment="ESC is running" inMemoryType="bitfield1" name="running" />
</Structure>
<Structure comment="Warning bits associated with the legacy (gen-1) ESC" file="LegacyESCDefines" name="LegacyWarningBits">
<Data comment="Set if RPM signal is not detected" inMemoryType="bitfield1" name="noRPMSignal" />
<Data comment="Set if the ESC motor speed exceeds the configured warning threshold" inMemoryType="bitfield1" name="overspeed" />
<Data comment="Set if the ESC motor current (positive or negative) exceeds the configured warning threshold" inMemoryType="bitfield1" name="overcurrent" />
<Data comment="Set if the internal ESC temperature is above the warning threshold" inMemoryType="bitfield1" name="escTemperature" />
<Data comment="Set if the motor temperature is above the warning threshold" inMemoryType="bitfield1" name="motorTemperature" />
<Data comment="Set if the input voltage is below the minimum threshold" inMemoryType="bitfield1" name="undervoltage" />
<Data comment="Set if the input voltage is above the maximum threshold" inMemoryType="bitfield1" name="overvoltage" />
<Data comment="Set if hardware PWM input is enabled but invalid" inMemoryType="bitfield1" name="invalidPWMsignal" />
</Structure>
<Structure comment="Error bits associated with the legacy (gen-1) ESC" file="LegacyESCDefines" name="LegacyErrorBits">
<Data comment="Set if communication link to the motor controller is lost" inMemoryType="bitfield1" name="linkError" />
<Data comment="Set if the ESC has detected an overcurrent event and is actively folding back duty cycle" inMemoryType="bitfield1" name="foldback" />
<Data comment="Set if the settings checksum does not match the programmed values" inMemoryType="bitfield1" name="settingsChecksum" />
<Data comment="Set if the motor settings are invalid" inMemoryType="bitfield1" name="motorSettings" />
<Data comment="Reserved for future use" inMemoryType="bitfield1" name="reservedD" />
<Data comment="Reserved for future use" inMemoryType="bitfield1" name="reservedE" />
<Data comment="Reserved for future use" inMemoryType="bitfield1" name="reservedF" />
<Data comment="Reserved for future use" inMemoryType="bitfield1" name="reservedG" />
</Structure>
<Packet ID="PKT_ESC_STATUS_A" comment="Legacy (gen-1) definition for the STATUS_A packet" file="LegacyESCPackets" name="LegacyStatusA" parameterInterface="true">
<Data checkConstant="true" comment="Set to 0 to indicate a Gen-2 ESC" constant="0" encodedType="bitfield1" inMemoryType="null" name="version" />
<Data comment="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." encodedType="bitfield7" inMemoryType="unsigned8" name="mode" />
<Data comment="ESC status bits" name="status" struct="LegacyStatusBits" />
<Data comment="ESC warning bits" name="warnings" struct="LegacyWarningBits" />
<Data comment="ESC *error* bits" name="errors" struct="LegacyErrorBits" />
<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>
<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="0xF6" />
<value comment="Mark the current settings as valid" name="VALIDATE_SETTINGS" value="0xF7" />
<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="null" 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="Settings checksum does not match programmed value" encodedType="bitfield1" inMemoryType="bool" name="settingsChecksum" />
<Data comment="Reserved for future use" constant="0" encodedType="bitfield1" 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="bool" name="failedStart" />
<Data comment="Lost commutation" encodedType="bitfield1" inMemoryType="bool" name="commutation" />
<Data comment="Set if hall sensor error detected" encodedType="bitfield1" inMemoryType="bool" name="hallSensor" />
<Data comment="Current exceeded hard-limit" encodedType="bitfield1" inMemoryType="bool" name="overcurrent" />
<Data comment="Temperature exceeded hard-limit" encodedType="bitfield1" inMemoryType="bool" name="overtemperature" />
<Data comment="Motor commutation speed exceeded hard-limit" encodedType="bitfield1" inMemoryType="bool" name="overspeed" />
<Data comment="Motor stopped due to high demag angle" encodedType="bitfield1" inMemoryType="bool" name="demag" />
<Data comment="Reserved for future use" constant="0" encodedType="bitfield8" inMemoryType="null" name="reservedA" />
<Data comment="Reserved for future use" constant="0" encodedType="bitfield1" inMemoryType="null" name="reservedB" />
</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 PKT_ESC_SETPOINT_2 PKT_ESC_SETPOINT_3 PKT_ESC_SETPOINT_4 PKT_ESC_SETPOINT_5 PKT_ESC_SETPOINT_6 PKT_ESC_SETPOINT_7 PKT_ESC_SETPOINT_8 PKT_ESC_SETPOINT_9 PKT_ESC_SETPOINT_10 PKT_ESC_SETPOINT_11 PKT_ESC_SETPOINT_12 PKT_ESC_SETPOINT_13 PKT_ESC_SETPOINT_14 PKT_ESC_SETPOINT_15 PKT_ESC_SETPOINT_16" 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="ValidateSettings">
<Data checkConstant="true" constant="CMD_ESC_VALIDATE_SETTINGS" encodedType="unsigned8" inMemoryType="null" name="command" />
<Data checkConstant="true" constant="0x1A" encodedType="unsigned8" inMemoryType="null" name="validateSeqA" />
<Data checkConstant="true" constant="0x2B" encodedType="unsigned8" inMemoryType="null" name="validateSeqB" />
<Data checkConstant="true" constant="0x3C" encodedType="unsigned8" inMemoryType="null" name="validateSeqC" />
</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" structureInterface="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" structureInterface="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" structureInterface="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" structureInterface="true">
<Data comment="Set if the ESC settings are locked" encodedType="bitfield1" inMemoryType="bool" name="settingsLocked" />
<Data comment="Version of EEPROM data" encodedType="bitfield7" inMemoryType="unsigned8" name="version" range="1 to 127" />
<Data comment="Size of settings data" inMemoryType="unsigned16" name="size" />
<Data comment="Settings checksum" inMemoryType="unsigned16" name="checksum" />
<Data comment="Validated settings checksum" default="0" inMemoryType="unsigned16" name="validatedChecksum" />
</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>