ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/ESCPackets.c

1788 lines
66 KiB
C

// ESCPackets.c 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/>.
*/
#include "ESCPackets.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Encode a ESC_TelemetryConfig_t structure into a byte array
*
* Telemetry settings (storage class)
* \param _pg_data points to the byte array to add encoded data to
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes.
* \param _pg_user is the data to encode in the byte array
*/
void encodeESC_TelemetryConfig_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_TelemetryConfig_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Telemetry period
uint8ToBytes(_pg_user->period, _pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
uint8ToBytes(_pg_user->silence, _pg_data, &_pg_byteindex);
// Bitfield describing which telemetry packets are enabled
encodeESC_TelemetryPackets_t(_pg_data, &_pg_byteindex, &_pg_user->packets);
*_pg_bytecount = _pg_byteindex;
}// encodeESC_TelemetryConfig_t
/*!
* \brief Decode a ESC_TelemetryConfig_t structure from a byte array
*
* Telemetry settings (storage class)
* \param _pg_data points to the byte array to decoded data from
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
* \param _pg_user is the data to decode from the byte array
* \return 1 if the data are decoded, else 0. If 0 is returned _pg_bytecount will not be updated.
*/
int decodeESC_TelemetryConfig_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_TelemetryConfig_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Telemetry period
_pg_user->period = uint8FromBytes(_pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
_pg_user->silence = uint8FromBytes(_pg_data, &_pg_byteindex);
// Bitfield describing which telemetry packets are enabled
if(decodeESC_TelemetryPackets_t(_pg_data, &_pg_byteindex, &_pg_user->packets) == 0)
return 0;
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_TelemetryConfig_t
/*!
* \brief Set a ESC_TelemetryConfig_t structure to initial values.
*
* Set a ESC_TelemetryConfig_t structure to initial values. Not all fields are set,
* only those which the protocol specifies.
* \param _pg_user is the structure whose data are set to initial values
*/
void initESC_TelemetryConfig_t(ESC_TelemetryConfig_t* _pg_user)
{
// Telemetry period
_pg_user->period = 4;
// Telemetry silence period (delay after RESET before telemetry data is sent)
_pg_user->silence = 20;
// Bitfield describing which telemetry packets are enabled
initESC_TelemetryPackets_t(&_pg_user->packets);
}// initESC_TelemetryConfig_t
/*!
* \brief Verify a ESC_TelemetryConfig_t structure has acceptable values.
*
* Verify a ESC_TelemetryConfig_t structure has acceptable values. Not all fields are
* verified, only those which the protocol specifies. Fields which are outside
* the allowable range are changed to the maximum or minimum allowable value.
* \param _pg_user is the structure whose data are verified
* \return 1 if all verifiable data where valid, else 0 if data had to be corrected
*/
int verifyESC_TelemetryConfig_t(ESC_TelemetryConfig_t* _pg_user)
{
int _pg_good = 1;
// Telemetry period
if(_pg_user->period > 250)
{
_pg_user->period = 250;
_pg_good = 0;
}
// Telemetry silence period (delay after RESET before telemetry data is sent)
if(_pg_user->silence > 250)
{
_pg_user->silence = 250;
_pg_good = 0;
}
return _pg_good;
}// verifyESC_TelemetryConfig_t
/*!
* \brief Create the ESC_TelemetryConfig packet
*
* Telemetry settings (storage class)
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_TelemetryConfigPacketStructure(void* _pg_pkt, const ESC_TelemetryConfig_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Telemetry period
uint8ToBytes(_pg_user->period, _pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
uint8ToBytes(_pg_user->silence, _pg_data, &_pg_byteindex);
// Bitfield describing which telemetry packets are enabled
encodeESC_TelemetryPackets_t(_pg_data, &_pg_byteindex, &_pg_user->packets);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_TelemetryConfigPacketID());
}
/*!
* \brief Decode the ESC_TelemetryConfig packet
*
* Telemetry settings (storage class)
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_TelemetryConfigPacketStructure(const void* _pg_pkt, ESC_TelemetryConfig_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_TelemetryConfigPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_TelemetryConfigMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// Telemetry period
_pg_user->period = uint8FromBytes(_pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
_pg_user->silence = uint8FromBytes(_pg_data, &_pg_byteindex);
// Bitfield describing which telemetry packets are enabled
if(decodeESC_TelemetryPackets_t(_pg_data, &_pg_byteindex, &_pg_user->packets) == 0)
return 0;
return 1;
}
/*!
* \brief Create the ESC_TelemetryConfig packet
*
* Telemetry settings (storage class)
* \param _pg_pkt points to the packet which will be created by this function
* \param period is Telemetry period
* \param silence is Telemetry silence period (delay after RESET before telemetry data is sent)
* \param packets is Bitfield describing which telemetry packets are enabled
*/
void encodeESC_TelemetryConfigPacket(void* _pg_pkt, uint8_t period, uint8_t silence, const ESC_TelemetryPackets_t* packets)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Telemetry period
uint8ToBytes(period, _pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
uint8ToBytes(silence, _pg_data, &_pg_byteindex);
// Bitfield describing which telemetry packets are enabled
encodeESC_TelemetryPackets_t(_pg_data, &_pg_byteindex, packets);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_TelemetryConfigPacketID());
}
/*!
* \brief Decode the ESC_TelemetryConfig packet
*
* Telemetry settings (storage class)
* \param _pg_pkt points to the packet being decoded by this function
* \param period receives Telemetry period
* \param silence receives Telemetry silence period (delay after RESET before telemetry data is sent)
* \param packets receives Bitfield describing which telemetry packets are enabled
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_TelemetryConfigPacket(const void* _pg_pkt, uint8_t* period, uint8_t* silence, ESC_TelemetryPackets_t* packets)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_TelemetryConfigPacketID())
return 0;
if(_pg_numbytes < getESC_TelemetryConfigMinDataLength())
return 0;
// Telemetry period
*period = uint8FromBytes(_pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
*silence = uint8FromBytes(_pg_data, &_pg_byteindex);
// Bitfield describing which telemetry packets are enabled
if(decodeESC_TelemetryPackets_t(_pg_data, &_pg_byteindex, packets) == 0)
return 0;
return 1;
}
/*!
* \brief Create the ESC_CommandMultipleESCs packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param pwmValueA is The PWM (pulse width) command for ESC with CAN ID 1
* \param pwmValueB is The PWM (pulse width) command for ESC with CAN ID 2
* \param pwmValueC is The PWM (pulse width) command for ESC with CAN ID 3
* \param pwmValueD is The PWM (pulse width) command for ESC with CAN ID 4
* \param id is the packet identifier for _pg_pkt
*/
void encodeESC_CommandMultipleESCsPacket(void* _pg_pkt, uint16_t pwmValueA, uint16_t pwmValueB, uint16_t pwmValueC, uint16_t pwmValueD, uint32_t _pg_id)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// The PWM (pulse width) command for ESC with CAN ID 1
uint16ToBeBytes(pwmValueA, _pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 2
uint16ToBeBytes(pwmValueB, _pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 3
uint16ToBeBytes(pwmValueC, _pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 4
uint16ToBeBytes(pwmValueD, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, _pg_id);
}
/*!
* \brief Decode the ESC_CommandMultipleESCs packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param pwmValueA receives The PWM (pulse width) command for ESC with CAN ID 1
* \param pwmValueB receives The PWM (pulse width) command for ESC with CAN ID 2
* \param pwmValueC receives The PWM (pulse width) command for ESC with CAN ID 3
* \param pwmValueD receives The PWM (pulse width) command for ESC with CAN ID 4
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_CommandMultipleESCsPacket(const void* _pg_pkt, uint16_t* pwmValueA, uint16_t* pwmValueB, uint16_t* pwmValueC, uint16_t* pwmValueD)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier, multiple options exist
uint32_t packetid = getESCVelocityPacketID(_pg_pkt);
if( packetid != PKT_ESC_SETPOINT_1 &&
packetid != PKT_ESC_SETPOINT_2 &&
packetid != PKT_ESC_SETPOINT_3 &&
packetid != PKT_ESC_SETPOINT_4 &&
packetid != PKT_ESC_SETPOINT_5 &&
packetid != PKT_ESC_SETPOINT_6 )
return 0;
if(_pg_numbytes < getESC_CommandMultipleESCsMinDataLength())
return 0;
// The PWM (pulse width) command for ESC with CAN ID 1
*pwmValueA = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 2
*pwmValueB = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 3
*pwmValueC = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 4
*pwmValueD = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Disable packet
*
* Send this packet to the ESC to disable it. The ESC will not accept PWM/RPM
* commands until it is re-enabled.
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_DisablePacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// This value must be set for the command to be accepted
uint8ToBytes((uint8_t)(ESC_DISABLE_A), _pg_data, &_pg_byteindex);
// This value must be set for the command to be accepted
uint8ToBytes((uint8_t)(ESC_DISABLE_B), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_DisablePacketID());
}
/*!
* \brief Decode the ESC_Disable packet
*
* Send this packet to the ESC to disable it. The ESC will not accept PWM/RPM
* commands until it is re-enabled.
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_DisablePacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_DisablePacketID())
return 0;
if(_pg_numbytes < getESC_DisableMinDataLength())
return 0;
// This value must be set for the command to be accepted
// Decoded value must be ESC_DISABLE_A
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_DISABLE_A)
return 0;
// This value must be set for the command to be accepted
// Decoded value must be ESC_DISABLE_B
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_DISABLE_B)
return 0;
return 1;
}
/*!
* \brief Create the ESC_Enable packet
*
* Send this packet to the ESC to enable it. The ESC will be placed in Standby
* mode.
* \param _pg_pkt points to the packet which will be created by this function
*/
void encodeESC_EnablePacket(void* _pg_pkt)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// This value must be set for the command to be accepted
uint8ToBytes((uint8_t)(ESC_ENABLE_A), _pg_data, &_pg_byteindex);
// This value must be set for the command to be included
uint8ToBytes((uint8_t)(ESC_ENABLE_B), _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_EnablePacketID());
}
/*!
* \brief Decode the ESC_Enable packet
*
* Send this packet to the ESC to enable it. The ESC will be placed in Standby
* mode.
* \param _pg_pkt points to the packet being decoded by this function
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_EnablePacket(const void* _pg_pkt)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_EnablePacketID())
return 0;
if(_pg_numbytes < getESC_EnableMinDataLength())
return 0;
// This value must be set for the command to be accepted
// Decoded value must be ESC_ENABLE_A
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_ENABLE_A)
return 0;
// This value must be set for the command to be included
// Decoded value must be ESC_ENABLE_B
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_ENABLE_B)
return 0;
return 1;
}
/*!
* \brief Create the ESC_PWMCommand packet
*
* Send a PWM (pulse width) command to an individual ESC. The pulse width value
* in specified in microseconds for compatibility with standard ESC interface.
* Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus.
* \param _pg_pkt points to the packet which will be created by this function
* \param pwmCommand is PWM command
*/
void encodeESC_PWMCommandPacket(void* _pg_pkt, uint16_t pwmCommand)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// PWM command
uint16ToBeBytes(pwmCommand, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_PWMCommandPacketID());
}
/*!
* \brief Decode the ESC_PWMCommand packet
*
* Send a PWM (pulse width) command to an individual ESC. The pulse width value
* in specified in microseconds for compatibility with standard ESC interface.
* Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus.
* \param _pg_pkt points to the packet being decoded by this function
* \param pwmCommand receives PWM command
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_PWMCommandPacket(const void* _pg_pkt, uint16_t* pwmCommand)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_PWMCommandPacketID())
return 0;
if(_pg_numbytes < getESC_PWMCommandMinDataLength())
return 0;
// PWM command
*pwmCommand = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_RPMCommand packet
*
* Send an RPM (speed) command to an individual ESC. Use the broadcast ID (0xFF)
* to send this command to all ESCs on the CAN bus
* \param _pg_pkt points to the packet which will be created by this function
* \param rpmCommand is RPM Command
*/
void encodeESC_RPMCommandPacket(void* _pg_pkt, uint16_t rpmCommand)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// RPM Command
uint16ToBeBytes(rpmCommand, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_RPMCommandPacketID());
}
/*!
* \brief Decode the ESC_RPMCommand packet
*
* Send an RPM (speed) command to an individual ESC. Use the broadcast ID (0xFF)
* to send this command to all ESCs on the CAN bus
* \param _pg_pkt points to the packet being decoded by this function
* \param rpmCommand receives RPM Command
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_RPMCommandPacket(const void* _pg_pkt, uint16_t* rpmCommand)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_RPMCommandPacketID())
return 0;
if(_pg_numbytes < getESC_RPMCommandMinDataLength())
return 0;
// RPM Command
*rpmCommand = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_StatusA packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_StatusAPacketStructure(void* _pg_pkt, const ESC_StatusA_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use.
uint8ToBytes(_pg_user->mode, _pg_data, &_pg_byteindex);
// ESC status bits
encodeESC_StatusBits_t(_pg_data, &_pg_byteindex, &_pg_user->status);
// ESC warning bits
encodeESC_WarningBits_t(_pg_data, &_pg_byteindex, &_pg_user->warnings);
// ESC *error* bits
encodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->errors);
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16ToBeBytes(_pg_user->command, _pg_data, &_pg_byteindex);
// Motor speed
uint16ToBeBytes(_pg_user->rpm, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusAPacketID());
}
/*!
* \brief Decode the ESC_StatusA packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_StatusAPacketStructure(const void* _pg_pkt, ESC_StatusA_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_StatusAPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_StatusAMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// 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.
_pg_user->mode = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC status bits
if(decodeESC_StatusBits_t(_pg_data, &_pg_byteindex, &_pg_user->status) == 0)
return 0;
// ESC warning bits
if(decodeESC_WarningBits_t(_pg_data, &_pg_byteindex, &_pg_user->warnings) == 0)
return 0;
// ESC *error* bits
if(decodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->errors) == 0)
return 0;
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
_pg_user->command = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Motor speed
_pg_user->rpm = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_StatusA packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param mode is ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use.
* \param status is ESC status bits
* \param warnings is ESC warning bits
* \param errors is ESC *error* bits
* \param command is ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
* \param rpm is Motor speed
*/
void encodeESC_StatusAPacket(void* _pg_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)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use.
uint8ToBytes(mode, _pg_data, &_pg_byteindex);
// ESC status bits
encodeESC_StatusBits_t(_pg_data, &_pg_byteindex, status);
// ESC warning bits
encodeESC_WarningBits_t(_pg_data, &_pg_byteindex, warnings);
// ESC *error* bits
encodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, errors);
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16ToBeBytes(command, _pg_data, &_pg_byteindex);
// Motor speed
uint16ToBeBytes(rpm, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusAPacketID());
}
/*!
* \brief Decode the ESC_StatusA packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param mode receives ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use.
* \param status receives ESC status bits
* \param warnings receives ESC warning bits
* \param errors receives ESC *error* bits
* \param command receives ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
* \param rpm receives Motor speed
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_StatusAPacket(const void* _pg_pkt, uint8_t* mode, ESC_StatusBits_t* status, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors, uint16_t* command, uint16_t* rpm)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_StatusAPacketID())
return 0;
if(_pg_numbytes < getESC_StatusAMinDataLength())
return 0;
// 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.
*mode = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC status bits
if(decodeESC_StatusBits_t(_pg_data, &_pg_byteindex, status) == 0)
return 0;
// ESC warning bits
if(decodeESC_WarningBits_t(_pg_data, &_pg_byteindex, warnings) == 0)
return 0;
// ESC *error* bits
if(decodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, errors) == 0)
return 0;
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
*command = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Motor speed
*rpm = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_StatusB packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_StatusBPacketStructure(void* _pg_pkt, const ESC_StatusB_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC Rail Voltage
uint16ToBeBytes(_pg_user->voltage, _pg_data, &_pg_byteindex);
// ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
int16ToBeBytes(_pg_user->current, _pg_data, &_pg_byteindex);
// ESC Motor Duty Cycle
uint16ToBeBytes(_pg_user->dutyCycle, _pg_data, &_pg_byteindex);
// ESC Board Temperature
int8ToBytes(_pg_user->escTemperature, _pg_data, &_pg_byteindex);
// ESC Motor Temperature
uint8ToBytes(_pg_user->motorTemperature, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusBPacketID());
}
/*!
* \brief Decode the ESC_StatusB packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_StatusBPacketStructure(const void* _pg_pkt, ESC_StatusB_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_StatusBPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_StatusBMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// ESC Rail Voltage
_pg_user->voltage = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
_pg_user->current = int16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Motor Duty Cycle
_pg_user->dutyCycle = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Board Temperature
_pg_user->escTemperature = int8FromBytes(_pg_data, &_pg_byteindex);
// ESC Motor Temperature
_pg_user->motorTemperature = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_StatusB packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param voltage is ESC Rail Voltage
* \param current is ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
* \param dutyCycle is ESC Motor Duty Cycle
* \param escTemperature is ESC Board Temperature
* \param motorTemperature is ESC Motor Temperature
*/
void encodeESC_StatusBPacket(void* _pg_pkt, uint16_t voltage, int16_t current, uint16_t dutyCycle, int8_t escTemperature, uint8_t motorTemperature)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC Rail Voltage
uint16ToBeBytes(voltage, _pg_data, &_pg_byteindex);
// ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
int16ToBeBytes(current, _pg_data, &_pg_byteindex);
// ESC Motor Duty Cycle
uint16ToBeBytes(dutyCycle, _pg_data, &_pg_byteindex);
// ESC Board Temperature
int8ToBytes(escTemperature, _pg_data, &_pg_byteindex);
// ESC Motor Temperature
uint8ToBytes(motorTemperature, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusBPacketID());
}
/*!
* \brief Decode the ESC_StatusB packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param voltage receives ESC Rail Voltage
* \param current receives ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
* \param dutyCycle receives ESC Motor Duty Cycle
* \param escTemperature receives ESC Board Temperature
* \param motorTemperature receives ESC Motor Temperature
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_StatusBPacket(const void* _pg_pkt, uint16_t* voltage, int16_t* current, uint16_t* dutyCycle, int8_t* escTemperature, uint8_t* motorTemperature)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_StatusBPacketID())
return 0;
if(_pg_numbytes < getESC_StatusBMinDataLength())
return 0;
// ESC Rail Voltage
*voltage = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
*current = int16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Motor Duty Cycle
*dutyCycle = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Board Temperature
*escTemperature = int8FromBytes(_pg_data, &_pg_byteindex);
// ESC Motor Temperature
*motorTemperature = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Accelerometer packet
*
* 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
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_AccelerometerPacketStructure(void* _pg_pkt, const ESC_Accelerometer_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// X axis acceleration value
int16ToBeBytes(_pg_user->xAcc, _pg_data, &_pg_byteindex);
// Y axis acceleration value
int16ToBeBytes(_pg_user->yAcc, _pg_data, &_pg_byteindex);
// Z axis acceleration value
int16ToBeBytes(_pg_user->zAcc, _pg_data, &_pg_byteindex);
// Accelerometer full-scale range
uint8ToBytes(_pg_user->fullscale, _pg_data, &_pg_byteindex);
// Accelerometer measurement resolution, in 'bits'.
uint8ToBytes(_pg_user->resolution, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AccelerometerPacketID());
}
/*!
* \brief Decode the ESC_Accelerometer packet
*
* 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
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_AccelerometerPacketStructure(const void* _pg_pkt, ESC_Accelerometer_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_AccelerometerPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_AccelerometerMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// X axis acceleration value
_pg_user->xAcc = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Y axis acceleration value
_pg_user->yAcc = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Z axis acceleration value
_pg_user->zAcc = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Accelerometer full-scale range
_pg_user->fullscale = uint8FromBytes(_pg_data, &_pg_byteindex);
// Accelerometer measurement resolution, in 'bits'.
_pg_user->resolution = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Accelerometer packet
*
* 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
* \param _pg_pkt points to the packet which will be created by this function
* \param xAcc is X axis acceleration value
* \param yAcc is Y axis acceleration value
* \param zAcc is Z axis acceleration value
* \param fullscale is Accelerometer full-scale range
* \param resolution is Accelerometer measurement resolution, in 'bits'.
*/
void encodeESC_AccelerometerPacket(void* _pg_pkt, int16_t xAcc, int16_t yAcc, int16_t zAcc, uint8_t fullscale, uint8_t resolution)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// X axis acceleration value
int16ToBeBytes(xAcc, _pg_data, &_pg_byteindex);
// Y axis acceleration value
int16ToBeBytes(yAcc, _pg_data, &_pg_byteindex);
// Z axis acceleration value
int16ToBeBytes(zAcc, _pg_data, &_pg_byteindex);
// Accelerometer full-scale range
uint8ToBytes(fullscale, _pg_data, &_pg_byteindex);
// Accelerometer measurement resolution, in 'bits'.
uint8ToBytes(resolution, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AccelerometerPacketID());
}
/*!
* \brief Decode the ESC_Accelerometer packet
*
* 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
* \param _pg_pkt points to the packet being decoded by this function
* \param xAcc receives X axis acceleration value
* \param yAcc receives Y axis acceleration value
* \param zAcc receives Z axis acceleration value
* \param fullscale receives Accelerometer full-scale range
* \param resolution receives Accelerometer measurement resolution, in 'bits'.
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_AccelerometerPacket(const void* _pg_pkt, int16_t* xAcc, int16_t* yAcc, int16_t* zAcc, uint8_t* fullscale, uint8_t* resolution)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_AccelerometerPacketID())
return 0;
if(_pg_numbytes < getESC_AccelerometerMinDataLength())
return 0;
// X axis acceleration value
*xAcc = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Y axis acceleration value
*yAcc = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Z axis acceleration value
*zAcc = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Accelerometer full-scale range
*fullscale = uint8FromBytes(_pg_data, &_pg_byteindex);
// Accelerometer measurement resolution, in 'bits'.
*resolution = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Address packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_AddressPacketStructure(void* _pg_pkt, const ESC_Address_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC hardware revision
uint8ToBytes(_pg_user->HardwareRevision, _pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
uint24ToBeBytes((uint32_t)(_pg_user->SerialNumber), _pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
uint16ToBeBytes(_pg_user->UserIDA, _pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
uint16ToBeBytes(_pg_user->UserIDB, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AddressPacketID());
}
/*!
* \brief Decode the ESC_Address packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_AddressPacketStructure(const void* _pg_pkt, ESC_Address_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_AddressPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_AddressMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// ESC hardware revision
_pg_user->HardwareRevision = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
_pg_user->SerialNumber = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
_pg_user->UserIDA = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
_pg_user->UserIDB = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Address packet
*
* 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.
* \param _pg_pkt points to the packet which will be created by this function
* \param HardwareRevision is ESC hardware revision
* \param SerialNumber is ESC Serial Number (OTP - not configurable by user)
* \param UserIDA is User ID Value A - user can set this value to any value
* \param UserIDB is User ID Value B - user can set this value to any value
*/
void encodeESC_AddressPacket(void* _pg_pkt, uint8_t HardwareRevision, uint32_t SerialNumber, uint16_t UserIDA, uint16_t UserIDB)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC hardware revision
uint8ToBytes(HardwareRevision, _pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
uint24ToBeBytes((uint32_t)(SerialNumber), _pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
uint16ToBeBytes(UserIDA, _pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
uint16ToBeBytes(UserIDB, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AddressPacketID());
}
/*!
* \brief Decode the ESC_Address packet
*
* 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.
* \param _pg_pkt points to the packet being decoded by this function
* \param HardwareRevision receives ESC hardware revision
* \param SerialNumber receives ESC Serial Number (OTP - not configurable by user)
* \param UserIDA receives User ID Value A - user can set this value to any value
* \param UserIDB receives User ID Value B - user can set this value to any value
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_AddressPacket(const void* _pg_pkt, uint8_t* HardwareRevision, uint32_t* SerialNumber, uint16_t* UserIDA, uint16_t* UserIDB)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_AddressPacketID())
return 0;
if(_pg_numbytes < getESC_AddressMinDataLength())
return 0;
// ESC hardware revision
*HardwareRevision = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
*SerialNumber = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
*UserIDA = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
*UserIDB = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Title packet
*
* This packet contains a zero-terminated string (max-length 8) used to identify
* the particular ESC.
* \param _pg_pkt points to the packet which will be created by this function
* \param ESCTitle is Description of this ESC
*/
void encodeESC_TitlePacket(void* _pg_pkt, const uint8_t ESCTitle[8])
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
unsigned _pg_i = 0;
// Description of this ESC
for(_pg_i = 0; _pg_i < 8; _pg_i++)
uint8ToBytes(ESCTitle[_pg_i], _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_TitlePacketID());
}
/*!
* \brief Decode the ESC_Title packet
*
* This packet contains a zero-terminated string (max-length 8) used to identify
* the particular ESC.
* \param _pg_pkt points to the packet being decoded by this function
* \param ESCTitle receives Description of this ESC
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_TitlePacket(const void* _pg_pkt, uint8_t ESCTitle[8])
{
unsigned _pg_i = 0;
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_TitlePacketID())
return 0;
if(_pg_numbytes < getESC_TitleMinDataLength())
return 0;
// Description of this ESC
for(_pg_i = 0; _pg_i < 8; _pg_i++)
ESCTitle[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Firmware packet
*
* This packet contains the firmware version of the ESC
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_FirmwarePacketStructure(void* _pg_pkt, const ESC_Firmware_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Major firmware version number
uint8ToBytes(_pg_user->versionMajor, _pg_data, &_pg_byteindex);
// Minor firmware version numner
uint8ToBytes(_pg_user->versionMinor, _pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
uint8ToBytes(_pg_user->versionDay, _pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
uint8ToBytes(_pg_user->versionMonth, _pg_data, &_pg_byteindex);
// Firmware release date, year
uint16ToBeBytes(_pg_user->versionYear, _pg_data, &_pg_byteindex);
// Firmware checksum
uint16ToBeBytes(_pg_user->firmwareChecksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_FirmwarePacketID());
}
/*!
* \brief Decode the ESC_Firmware packet
*
* This packet contains the firmware version of the ESC
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_FirmwarePacketStructure(const void* _pg_pkt, ESC_Firmware_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_FirmwarePacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_FirmwareMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// Major firmware version number
_pg_user->versionMajor = uint8FromBytes(_pg_data, &_pg_byteindex);
// Minor firmware version numner
_pg_user->versionMinor = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
_pg_user->versionDay = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
_pg_user->versionMonth = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, year
_pg_user->versionYear = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Firmware checksum
_pg_user->firmwareChecksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_Firmware packet
*
* This packet contains the firmware version of the ESC
* \param _pg_pkt points to the packet which will be created by this function
* \param versionMajor is Major firmware version number
* \param versionMinor is Minor firmware version numner
* \param versionDay is Firmware release date, day-of-month
* \param versionMonth is Firmware release data, month-of-year
* \param versionYear is Firmware release date, year
* \param firmwareChecksum is Firmware checksum
*/
void encodeESC_FirmwarePacket(void* _pg_pkt, uint8_t versionMajor, uint8_t versionMinor, uint8_t versionDay, uint8_t versionMonth, uint16_t versionYear, uint16_t firmwareChecksum)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Major firmware version number
uint8ToBytes(versionMajor, _pg_data, &_pg_byteindex);
// Minor firmware version numner
uint8ToBytes(versionMinor, _pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
uint8ToBytes(versionDay, _pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
uint8ToBytes(versionMonth, _pg_data, &_pg_byteindex);
// Firmware release date, year
uint16ToBeBytes(versionYear, _pg_data, &_pg_byteindex);
// Firmware checksum
uint16ToBeBytes(firmwareChecksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_FirmwarePacketID());
}
/*!
* \brief Decode the ESC_Firmware packet
*
* This packet contains the firmware version of the ESC
* \param _pg_pkt points to the packet being decoded by this function
* \param versionMajor receives Major firmware version number
* \param versionMinor receives Minor firmware version numner
* \param versionDay receives Firmware release date, day-of-month
* \param versionMonth receives Firmware release data, month-of-year
* \param versionYear receives Firmware release date, year
* \param firmwareChecksum receives Firmware checksum
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_FirmwarePacket(const void* _pg_pkt, uint8_t* versionMajor, uint8_t* versionMinor, uint8_t* versionDay, uint8_t* versionMonth, uint16_t* versionYear, uint16_t* firmwareChecksum)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_FirmwarePacketID())
return 0;
if(_pg_numbytes < getESC_FirmwareMinDataLength())
return 0;
// Major firmware version number
*versionMajor = uint8FromBytes(_pg_data, &_pg_byteindex);
// Minor firmware version numner
*versionMinor = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
*versionDay = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
*versionMonth = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, year
*versionYear = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Firmware checksum
*firmwareChecksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_SystemInfo packet
*
* This packet contains system runtime information
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_SystemInfoPacketStructure(void* _pg_pkt, const ESC_SystemInfo_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Number of milliseconds since the ESC last experienced a reset/power-on event
uint32ToBeBytes(_pg_user->millisecondsSinceReset, _pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
uint8ToBytes(_pg_user->resetCode, _pg_data, &_pg_byteindex);
// Processor usage
uint8ToBytes(_pg_user->cpuOccupancy, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SystemInfoPacketID());
}
/*!
* \brief Decode the ESC_SystemInfo packet
*
* This packet contains system runtime information
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_SystemInfoPacketStructure(const void* _pg_pkt, ESC_SystemInfo_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_SystemInfoPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_SystemInfoMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// Number of milliseconds since the ESC last experienced a reset/power-on event
_pg_user->millisecondsSinceReset = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
_pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
_pg_user->resetCode = uint8FromBytes(_pg_data, &_pg_byteindex);
// Processor usage
_pg_user->cpuOccupancy = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_SystemInfo packet
*
* This packet contains system runtime information
* \param _pg_pkt points to the packet which will be created by this function
* \param millisecondsSinceReset is Number of milliseconds since the ESC last experienced a reset/power-on event
* \param powerCycles is Number of power cycle events that the ESC has experienced
* \param resetCode is Processor RESET code for debug purposes
* \param cpuOccupancy is Processor usage
*/
void encodeESC_SystemInfoPacket(void* _pg_pkt, uint32_t millisecondsSinceReset, uint16_t powerCycles, uint8_t resetCode, uint8_t cpuOccupancy)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Number of milliseconds since the ESC last experienced a reset/power-on event
uint32ToBeBytes(millisecondsSinceReset, _pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
uint16ToBeBytes(powerCycles, _pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
uint8ToBytes(resetCode, _pg_data, &_pg_byteindex);
// Processor usage
uint8ToBytes(cpuOccupancy, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SystemInfoPacketID());
}
/*!
* \brief Decode the ESC_SystemInfo packet
*
* This packet contains system runtime information
* \param _pg_pkt points to the packet being decoded by this function
* \param millisecondsSinceReset receives Number of milliseconds since the ESC last experienced a reset/power-on event
* \param powerCycles receives Number of power cycle events that the ESC has experienced
* \param resetCode receives Processor RESET code for debug purposes
* \param cpuOccupancy receives Processor usage
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_SystemInfoPacket(const void* _pg_pkt, uint32_t* millisecondsSinceReset, uint16_t* powerCycles, uint8_t* resetCode, uint8_t* cpuOccupancy)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_SystemInfoPacketID())
return 0;
if(_pg_numbytes < getESC_SystemInfoMinDataLength())
return 0;
// Number of milliseconds since the ESC last experienced a reset/power-on event
*millisecondsSinceReset = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
*powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
*resetCode = uint8FromBytes(_pg_data, &_pg_byteindex);
// Processor usage
*cpuOccupancy = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Set a ESC_TelemetrySettings_t structure to initial values.
*
* Set a ESC_TelemetrySettings_t structure to initial values. Not all fields are set,
* only those which the protocol specifies.
* \param _pg_user is the structure whose data are set to initial values
*/
void initESC_TelemetrySettings_t(ESC_TelemetrySettings_t* _pg_user)
{
// Telemetry settings
initESC_TelemetryConfig_t(&_pg_user->settings);
}// initESC_TelemetrySettings_t
/*!
* \brief Verify a ESC_TelemetrySettings_t structure has acceptable values.
*
* Verify a ESC_TelemetrySettings_t structure has acceptable values. Not all fields are
* verified, only those which the protocol specifies. Fields which are outside
* the allowable range are changed to the maximum or minimum allowable value.
* \param _pg_user is the structure whose data are verified
* \return 1 if all verifiable data where valid, else 0 if data had to be corrected
*/
int verifyESC_TelemetrySettings_t(ESC_TelemetrySettings_t* _pg_user)
{
int _pg_good = 1;
// Telemetry settings
if(!verifyESC_TelemetryConfig_t(&_pg_user->settings))
_pg_good = 0;
return _pg_good;
}// verifyESC_TelemetrySettings_t
/*!
* \brief Create the ESC_TelemetrySettings packet
*
* This packet contains the telemetry packet configuration
* \param _pg_pkt points to the packet which will be created by this function
* \param settings is Telemetry settings
*/
void encodeESC_TelemetrySettingsPacket(void* _pg_pkt, const ESC_TelemetryConfig_t* settings)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Telemetry settings
encodeESC_TelemetryConfig_t(_pg_data, &_pg_byteindex, settings);
// The API version of the ESC
stringToBytes(getESCVelocityVersion(), _pg_data, &_pg_byteindex, 5, 0);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_TelemetrySettingsPacketID());
}
/*!
* \brief Decode the ESC_TelemetrySettings packet
*
* This packet contains the telemetry packet configuration
* \param _pg_pkt points to the packet being decoded by this function
* \param settings receives Telemetry settings
* \param apiVersion receives The API version of the ESC
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_TelemetrySettingsPacket(const void* _pg_pkt, ESC_TelemetryConfig_t* settings, char apiVersion[5])
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_TelemetrySettingsPacketID())
return 0;
if(_pg_numbytes < getESC_TelemetrySettingsMinDataLength())
return 0;
// Telemetry settings
if(decodeESC_TelemetryConfig_t(_pg_data, &_pg_byteindex, settings) == 0)
return 0;
// The API version of the ESC
stringFromBytes(apiVersion, _pg_data, &_pg_byteindex, 5, 0);
return 1;
}
/*!
* \brief Create the ESC_EEPROMSettings packet
*
* This packet contains information on the non-volatile ESC settings
* \param _pg_pkt points to the packet which will be created by this function
* \param _pg_user points to the user data that will be encoded in _pg_pkt
*/
void encodeESC_EEPROMSettingsPacketStructure(void* _pg_pkt, const ESC_EEPROMSettings_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Version of EEPROM data
uint8ToBytes(_pg_user->version, _pg_data, &_pg_byteindex);
// Size of settings data
uint16ToBeBytes(_pg_user->size, _pg_data, &_pg_byteindex);
// Settings checksum
uint16ToBeBytes(_pg_user->checksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_EEPROMSettingsPacketID());
}
/*!
* \brief Decode the ESC_EEPROMSettings packet
*
* This packet contains information on the non-volatile ESC settings
* \param _pg_pkt points to the packet being decoded by this function
* \param _pg_user receives the data decoded from the packet
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_EEPROMSettingsPacketStructure(const void* _pg_pkt, ESC_EEPROMSettings_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_EEPROMSettingsPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_EEPROMSettingsMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// Version of EEPROM data
_pg_user->version = uint8FromBytes(_pg_data, &_pg_byteindex);
// Size of settings data
_pg_user->size = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Settings checksum
_pg_user->checksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
/*!
* \brief Create the ESC_EEPROMSettings packet
*
* This packet contains information on the non-volatile ESC settings
* \param _pg_pkt points to the packet which will be created by this function
* \param version is Version of EEPROM data
* \param size is Size of settings data
* \param checksum is Settings checksum
*/
void encodeESC_EEPROMSettingsPacket(void* _pg_pkt, uint8_t version, uint16_t size, uint16_t checksum)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Version of EEPROM data
uint8ToBytes(version, _pg_data, &_pg_byteindex);
// Size of settings data
uint16ToBeBytes(size, _pg_data, &_pg_byteindex);
// Settings checksum
uint16ToBeBytes(checksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_EEPROMSettingsPacketID());
}
/*!
* \brief Decode the ESC_EEPROMSettings packet
*
* This packet contains information on the non-volatile ESC settings
* \param _pg_pkt points to the packet being decoded by this function
* \param version receives Version of EEPROM data
* \param size receives Size of settings data
* \param checksum receives Settings checksum
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_EEPROMSettingsPacket(const void* _pg_pkt, uint8_t* version, uint16_t* size, uint16_t* checksum)
{
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_EEPROMSettingsPacketID())
return 0;
if(_pg_numbytes < getESC_EEPROMSettingsMinDataLength())
return 0;
// Version of EEPROM data
*version = uint8FromBytes(_pg_data, &_pg_byteindex);
// Size of settings data
*size = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Settings checksum
*checksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}
// end of ESCPackets.c