ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/ESCPackets.h

459 lines
18 KiB
C

// ESCPackets.h was generated by ProtoGen version 2.18.c
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _ESCPACKETS_H
#define _ESCPACKETS_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include "ESCVelocityProtocol.h"
#include "ESCDefines.h"
/*!
* Telemetry settings (storage class)
*/
typedef struct
{
uint8_t period; //!< Telemetry period
uint8_t silence; //!< Telemetry silence period (delay after RESET before telemetry data is sent)
ESC_TelemetryPackets_t packets; //!< Bitfield describing which telemetry packets are enabled
}ESC_TelemetryConfig_t;
// Initial and verify values for TelemetryConfig
#define ESCVelocity_TelemetryConfig_period_InitValue 4
#define ESCVelocity_TelemetryConfig_period_VerifyMax 250
#define ESCVelocity_TelemetryConfig_silence_InitValue 20
#define ESCVelocity_TelemetryConfig_silence_VerifyMax 250
//! Encode a ESC_TelemetryConfig_t structure into a byte array
void encodeESC_TelemetryConfig_t(uint8_t* data, int* bytecount, const ESC_TelemetryConfig_t* user);
//! Decode a ESC_TelemetryConfig_t structure from a byte array
int decodeESC_TelemetryConfig_t(const uint8_t* data, int* bytecount, ESC_TelemetryConfig_t* user);
//! Set a ESC_TelemetryConfig_t structure to initial values
void initESC_TelemetryConfig_t(ESC_TelemetryConfig_t* user);
//! Verify a ESC_TelemetryConfig_t structure has acceptable values
int verifyESC_TelemetryConfig_t(ESC_TelemetryConfig_t* user);
//! Create the ESC_TelemetryConfig packet
void encodeESC_TelemetryConfigPacketStructure(void* pkt, const ESC_TelemetryConfig_t* user);
//! Decode the ESC_TelemetryConfig packet
int decodeESC_TelemetryConfigPacketStructure(const void* pkt, ESC_TelemetryConfig_t* user);
//! Create the ESC_TelemetryConfig packet
void encodeESC_TelemetryConfigPacket(void* pkt, uint8_t period, uint8_t silence, const ESC_TelemetryPackets_t* packets);
//! Decode the ESC_TelemetryConfig packet
int decodeESC_TelemetryConfigPacket(const void* pkt, uint8_t* period, uint8_t* silence, ESC_TelemetryPackets_t* packets);
//! 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)
/*!
* 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.
*/
typedef struct
{
uint16_t pwmValueA; //!< The PWM (pulse width) command for ESC with CAN ID 1
uint16_t pwmValueB; //!< The PWM (pulse width) command for ESC with CAN ID 2
uint16_t pwmValueC; //!< The PWM (pulse width) command for ESC with CAN ID 3
uint16_t pwmValueD; //!< The PWM (pulse width) command for ESC with CAN ID 4
}ESC_CommandMultipleESCs_t;
//! Create the ESC_CommandMultipleESCs packet
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
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
void encodeESC_DisablePacket(void* pkt);
//! Decode the ESC_Disable packet
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
void encodeESC_EnablePacket(void* pkt);
//! Decode the ESC_Enable packet
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
void encodeESC_PWMCommandPacket(void* pkt, uint16_t pwmCommand);
//! Decode the ESC_PWMCommand packet
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
void encodeESC_RPMCommandPacket(void* pkt, uint16_t rpmCommand);
//! Decode the ESC_RPMCommand packet
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)
/*!
* 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 four bits are used for debugging and should be ignored for general use.
ESC_StatusBits_t status; //!< ESC status bits
ESC_WarningBits_t warnings; //!< ESC warning bits
ESC_ErrorBits_t errors; //!< ESC *error* bits
uint16_t command; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
}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
void encodeESC_StatusAPacket(void* pkt, uint8_t mode, const ESC_StatusBits_t* status, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors, uint16_t command, uint16_t rpm);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacket(const void* pkt, uint8_t* mode, ESC_StatusBits_t* status, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors, uint16_t* command, uint16_t* rpm);
//! 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 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
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
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)
/*!
* This packet contains raw accelerometer data from the ESC. It can be requested
* (polled) from the ESC by sending a zero-length packet of the same type. It
* can also be transmitted by the ESC at high-frequency using the high-frequency
* streaming functionality of the ESC
*/
typedef struct
{
int16_t xAcc; //!< X axis acceleration value
int16_t yAcc; //!< Y axis acceleration value
int16_t zAcc; //!< Z axis acceleration value
uint8_t fullscale; //!< Accelerometer full-scale range
uint8_t resolution; //!< Accelerometer measurement resolution, in 'bits'.
}ESC_Accelerometer_t;
//! Create the ESC_Accelerometer packet
void encodeESC_AccelerometerPacketStructure(void* pkt, const ESC_Accelerometer_t* user);
//! Decode the ESC_Accelerometer packet
int decodeESC_AccelerometerPacketStructure(const void* pkt, ESC_Accelerometer_t* user);
//! Create the ESC_Accelerometer packet
void encodeESC_AccelerometerPacket(void* pkt, int16_t xAcc, int16_t yAcc, int16_t zAcc, uint8_t fullscale, uint8_t resolution);
//! Decode the ESC_Accelerometer packet
int decodeESC_AccelerometerPacket(const void* pkt, int16_t* xAcc, int16_t* yAcc, int16_t* zAcc, uint8_t* fullscale, uint8_t* resolution);
//! return the packet ID for the ESC_Accelerometer packet
#define getESC_AccelerometerPacketID() (PKT_ESC_ACCELEROMETER)
//! return the minimum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMinDataLength() (8)
//! return the maximum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMaxDataLength() (8)
/*!
* This packet contains the serial number for the ESC. Additionally there are
* two extra values (each 16-bit) which can be programmed by the user for any
* purpose.
*/
typedef struct
{
uint8_t HardwareRevision; //!< ESC hardware revision
uint32_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
void encodeESC_AddressPacket(void* pkt, uint8_t HardwareRevision, uint32_t SerialNumber, uint16_t UserIDA, uint16_t UserIDB);
//! Decode the ESC_Address packet
int decodeESC_AddressPacket(const void* pkt, uint8_t* HardwareRevision, uint32_t* SerialNumber, uint16_t* UserIDA, uint16_t* UserIDB);
//! 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)
//! Create the ESC_Title packet
void encodeESC_TitlePacket(void* pkt, const uint8_t ESCTitle[8]);
//! Decode the ESC_Title packet
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
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
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
void encodeESC_SystemInfoPacket(void* pkt, uint32_t millisecondsSinceReset, uint16_t powerCycles, uint8_t resetCode, uint8_t cpuOccupancy);
//! Decode the ESC_SystemInfo packet
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;
//! Set a ESC_TelemetrySettings_t structure to initial values
void initESC_TelemetrySettings_t(ESC_TelemetrySettings_t* user);
//! Verify a ESC_TelemetrySettings_t structure has acceptable values
int verifyESC_TelemetrySettings_t(ESC_TelemetrySettings_t* user);
//! Create the ESC_TelemetrySettings packet
void encodeESC_TelemetrySettingsPacket(void* pkt, const ESC_TelemetryConfig_t* settings);
//! Decode the ESC_TelemetrySettings packet
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
{
uint8_t version; //!< Version of EEPROM data
uint16_t size; //!< Size of settings data
uint16_t checksum; //!< 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
void encodeESC_EEPROMSettingsPacket(void* pkt, uint8_t version, uint16_t size, uint16_t checksum);
//! Decode the ESC_EEPROMSettings packet
int decodeESC_EEPROMSettingsPacket(const void* pkt, uint8_t* version, uint16_t* size, uint16_t* checksum);
//! 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() (5)
#ifdef __cplusplus
}
#endif
#endif