ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/ESCPackets.c

3006 lines
112 KiB
C

// ESCPackets.c was generated by ProtoGen version 3.2.a
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters
*/
#include "ESCPackets.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Create the ESC_Config packet
*
* General ESC configuration parameters
* \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_ConfigPacketStructure(void* _pg_pkt, const ESC_Config_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// 1 = ESC is inhibited (disabled) on startup
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->swInhibit == true) ? 1 : 0) << 7;
// 1 = ESC will respond to PICCOLO autopilot commands
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piccoloCommands == true) ? 1 : 0) << 6;
// 1 = ESC will accept broadcast command messages
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->broadcastCommands == true) ? 1 : 0) << 5;
// Command input source priority, refer to enumeration ESCCommandPriorities
// Range of commandInputPriority is 0 to 3.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->commandInputPriority, 3) << 3;
// Reserved for future use
// External motor temperature sensor configuration
// Range of motorTempSensor is 0 to 3.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->motorTempSensor, 3);
_pg_byteindex += 1; // close bit field
// 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
// Range of keepalive is 0 to 255.
uint8ToBytes(_pg_user->keepalive, _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint16ToBeBytes((uint16_t)(0), _pg_data, &_pg_byteindex);
// Range of motorBeepMode is 0 to 7.
_pg_data[_pg_byteindex] = (uint8_t)limitMax(_pg_user->motorBeepMode, 7) << 5;
// Motor beep volume
// Range of motorBeepVolume is 0 to 31.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->motorBeepVolume, 31);
_pg_byteindex += 1; // close bit field
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_ConfigPacketID());
}// encodeESC_ConfigPacketStructure
/*!
* \brief Decode the ESC_Config packet
*
* General ESC configuration parameters
* \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_ConfigPacketStructure(const void* _pg_pkt, ESC_Config_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_ConfigPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_ConfigMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// 1 = ESC is inhibited (disabled) on startup
_pg_user->swInhibit = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// 1 = ESC will respond to PICCOLO autopilot commands
_pg_user->piccoloCommands = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// 1 = ESC will accept broadcast command messages
_pg_user->broadcastCommands = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Command input source priority, refer to enumeration ESCCommandPriorities
// Range of commandInputPriority is 0 to 3.
_pg_user->commandInputPriority = ((_pg_data[_pg_byteindex] >> 3) & 0x3);
// Reserved for future use
// External motor temperature sensor configuration
// Range of motorTempSensor is 0 to 3.
_pg_user->motorTempSensor = ((_pg_data[_pg_byteindex]) & 0x3);
_pg_byteindex += 1; // close bit field
// 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
// Range of keepalive is 0 to 255.
_pg_user->keepalive = uint8FromBytes(_pg_data, &_pg_byteindex);
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 2;
// Range of motorBeepMode is 0 to 7.
_pg_user->motorBeepMode = (_pg_data[_pg_byteindex] >> 5);
// Motor beep volume
// Range of motorBeepVolume is 0 to 31.
_pg_user->motorBeepVolume = ((_pg_data[_pg_byteindex]) & 0x1F);
_pg_byteindex += 1; // close bit field
return 1;
}// decodeESC_ConfigPacketStructure
/*!
* \brief Create the ESC_Config packet
*
* General ESC configuration parameters
* \param _pg_pkt points to the packet which will be created by this function
* \param swInhibit is 1 = ESC is inhibited (disabled) on startup
* \param piccoloCommands is 1 = ESC will respond to PICCOLO autopilot commands
* \param broadcastCommands is 1 = ESC will accept broadcast command messages
* \param commandInputPriority is Command input source priority, refer to enumeration ESCCommandPriorities
* \param motorTempSensor is External motor temperature sensor configuration
* \param keepalive is 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
* \param motorBeepMode is
* \param motorBeepVolume is Motor beep volume
*/
void encodeESC_ConfigPacket(void* _pg_pkt, bool swInhibit, bool piccoloCommands, bool broadcastCommands, uint8_t commandInputPriority, uint8_t motorTempSensor, uint8_t keepalive, uint8_t motorBeepMode, uint8_t motorBeepVolume)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// 1 = ESC is inhibited (disabled) on startup
_pg_data[_pg_byteindex] = (uint8_t)((swInhibit == true) ? 1 : 0) << 7;
// 1 = ESC will respond to PICCOLO autopilot commands
_pg_data[_pg_byteindex] |= (uint8_t)((piccoloCommands == true) ? 1 : 0) << 6;
// 1 = ESC will accept broadcast command messages
_pg_data[_pg_byteindex] |= (uint8_t)((broadcastCommands == true) ? 1 : 0) << 5;
// Command input source priority, refer to enumeration ESCCommandPriorities
// Range of commandInputPriority is 0 to 3.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(commandInputPriority, 3) << 3;
// Reserved for future use
// External motor temperature sensor configuration
// Range of motorTempSensor is 0 to 3.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(motorTempSensor, 3);
_pg_byteindex += 1; // close bit field
// 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
// Range of keepalive is 0 to 255.
uint8ToBytes(keepalive, _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint16ToBeBytes((uint16_t)(0), _pg_data, &_pg_byteindex);
// Range of motorBeepMode is 0 to 7.
_pg_data[_pg_byteindex] = (uint8_t)limitMax(motorBeepMode, 7) << 5;
// Motor beep volume
// Range of motorBeepVolume is 0 to 31.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(motorBeepVolume, 31);
_pg_byteindex += 1; // close bit field
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_ConfigPacketID());
}// encodeESC_ConfigPacket
/*!
* \brief Decode the ESC_Config packet
*
* General ESC configuration parameters
* \param _pg_pkt points to the packet being decoded by this function
* \param swInhibit receives 1 = ESC is inhibited (disabled) on startup
* \param piccoloCommands receives 1 = ESC will respond to PICCOLO autopilot commands
* \param broadcastCommands receives 1 = ESC will accept broadcast command messages
* \param commandInputPriority receives Command input source priority, refer to enumeration ESCCommandPriorities
* \param motorTempSensor receives External motor temperature sensor configuration
* \param keepalive receives 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
* \param motorBeepMode receives
* \param motorBeepVolume receives Motor beep volume
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_ConfigPacket(const void* _pg_pkt, bool* swInhibit, bool* piccoloCommands, bool* broadcastCommands, uint8_t* commandInputPriority, uint8_t* motorTempSensor, uint8_t* keepalive, uint8_t* motorBeepMode, uint8_t* motorBeepVolume)
{
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_ConfigPacketID())
return 0;
if(_pg_numbytes < getESC_ConfigMinDataLength())
return 0;
// 1 = ESC is inhibited (disabled) on startup
(*swInhibit) = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// 1 = ESC will respond to PICCOLO autopilot commands
(*piccoloCommands) = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// 1 = ESC will accept broadcast command messages
(*broadcastCommands) = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Command input source priority, refer to enumeration ESCCommandPriorities
// Range of commandInputPriority is 0 to 3.
(*commandInputPriority) = ((_pg_data[_pg_byteindex] >> 3) & 0x3);
// Reserved for future use
// External motor temperature sensor configuration
// Range of motorTempSensor is 0 to 3.
(*motorTempSensor) = ((_pg_data[_pg_byteindex]) & 0x3);
_pg_byteindex += 1; // close bit field
// 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
// Range of keepalive is 0 to 255.
(*keepalive) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 2;
// Range of motorBeepMode is 0 to 7.
(*motorBeepMode) = (_pg_data[_pg_byteindex] >> 5);
// Motor beep volume
// Range of motorBeepVolume is 0 to 31.
(*motorBeepVolume) = ((_pg_data[_pg_byteindex]) & 0x1F);
_pg_byteindex += 1; // close bit field
return 1;
}// decodeESC_ConfigPacket
/*!
* \brief Encode a ESC_Config_t into a byte array
*
* General ESC configuration parameters
* \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_Config_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Config_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = ESC is inhibited (disabled) on startup
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->swInhibit == true) ? 1 : 0) << 7;
// 1 = ESC will respond to PICCOLO autopilot commands
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piccoloCommands == true) ? 1 : 0) << 6;
// 1 = ESC will accept broadcast command messages
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->broadcastCommands == true) ? 1 : 0) << 5;
// Command input source priority, refer to enumeration ESCCommandPriorities
// Range of commandInputPriority is 0 to 3.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->commandInputPriority, 3) << 3;
// Reserved for future use
// External motor temperature sensor configuration
// Range of motorTempSensor is 0 to 3.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->motorTempSensor, 3);
_pg_byteindex += 1; // close bit field
// 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
// Range of keepalive is 0 to 255.
uint8ToBytes(_pg_user->keepalive, _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// Reserved for future use
uint16ToBeBytes((uint16_t)(0), _pg_data, &_pg_byteindex);
// Range of motorBeepMode is 0 to 7.
_pg_data[_pg_byteindex] = (uint8_t)limitMax(_pg_user->motorBeepMode, 7) << 5;
// Motor beep volume
// Range of motorBeepVolume is 0 to 31.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->motorBeepVolume, 31);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_Config_t
/*!
* \brief Decode a ESC_Config_t from a byte array
*
* General ESC configuration parameters
* \param _pg_data points to the byte array to decoded data from
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
* \param _pg_user is the data to decode from the byte array
* \return 1 if the data are decoded, else 0.
*/
int decodeESC_Config_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Config_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = ESC is inhibited (disabled) on startup
_pg_user->swInhibit = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// 1 = ESC will respond to PICCOLO autopilot commands
_pg_user->piccoloCommands = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// 1 = ESC will accept broadcast command messages
_pg_user->broadcastCommands = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Command input source priority, refer to enumeration ESCCommandPriorities
// Range of commandInputPriority is 0 to 3.
_pg_user->commandInputPriority = ((_pg_data[_pg_byteindex] >> 3) & 0x3);
// Reserved for future use
// External motor temperature sensor configuration
// Range of motorTempSensor is 0 to 3.
_pg_user->motorTempSensor = ((_pg_data[_pg_byteindex]) & 0x3);
_pg_byteindex += 1; // close bit field
// 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
// Range of keepalive is 0 to 255.
_pg_user->keepalive = uint8FromBytes(_pg_data, &_pg_byteindex);
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 1;
// Reserved for future use
_pg_byteindex += 2;
// Range of motorBeepMode is 0 to 7.
_pg_user->motorBeepMode = (_pg_data[_pg_byteindex] >> 5);
// Motor beep volume
// Range of motorBeepVolume is 0 to 31.
_pg_user->motorBeepVolume = ((_pg_data[_pg_byteindex]) & 0x1F);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_Config_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 code (maps indirectly to a telemetry period value)
// Range of period is 0 to 255.
uint8ToBytes(_pg_user->period, _pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
// Range of silence is 0 to 255.
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());
}// encodeESC_TelemetryConfigPacketStructure
/*!
* \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 code (maps indirectly to a telemetry period value)
// Range of period is 0 to 255.
_pg_user->period = uint8FromBytes(_pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
// Range of silence is 0 to 255.
_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;
}// decodeESC_TelemetryConfigPacketStructure
/*!
* \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 code (maps indirectly to a telemetry period value)
* \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 code (maps indirectly to a telemetry period value)
// Range of period is 0 to 255.
uint8ToBytes(period, _pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
// Range of silence is 0 to 255.
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());
}// encodeESC_TelemetryConfigPacket
/*!
* \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 code (maps indirectly to a telemetry period value)
* \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 code (maps indirectly to a telemetry period value)
// Range of period is 0 to 255.
(*period) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
// Range of silence is 0 to 255.
(*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;
}// decodeESC_TelemetryConfigPacket
/*!
* \brief Encode a ESC_TelemetryConfig_t 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 code (maps indirectly to a telemetry period value)
// Range of period is 0 to 255.
uint8ToBytes(_pg_user->period, _pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
// Range of silence is 0 to 255.
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 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.
*/
int decodeESC_TelemetryConfig_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_TelemetryConfig_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Telemetry period code (maps indirectly to a telemetry period value)
// Range of period is 0 to 255.
_pg_user->period = uint8FromBytes(_pg_data, &_pg_byteindex);
// Telemetry silence period (delay after RESET before telemetry data is sent)
// Range of silence is 0 to 255.
_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 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
// Range of pwmValueA is 0 to 65535.
uint16ToBeBytes(pwmValueA, _pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 2
// Range of pwmValueB is 0 to 65535.
uint16ToBeBytes(pwmValueB, _pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 3
// Range of pwmValueC is 0 to 65535.
uint16ToBeBytes(pwmValueC, _pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 4
// Range of pwmValueD is 0 to 65535.
uint16ToBeBytes(pwmValueD, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, _pg_id);
}// encodeESC_CommandMultipleESCsPacket
/*!
* \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 &&
packetid != PKT_ESC_SETPOINT_7 &&
packetid != PKT_ESC_SETPOINT_8 &&
packetid != PKT_ESC_SETPOINT_9 &&
packetid != PKT_ESC_SETPOINT_10 &&
packetid != PKT_ESC_SETPOINT_11 &&
packetid != PKT_ESC_SETPOINT_12 &&
packetid != PKT_ESC_SETPOINT_13 &&
packetid != PKT_ESC_SETPOINT_14 &&
packetid != PKT_ESC_SETPOINT_15 &&
packetid != PKT_ESC_SETPOINT_16 )
return 0;
if(_pg_numbytes < getESC_CommandMultipleESCsMinDataLength())
return 0;
// The PWM (pulse width) command for ESC with CAN ID 1
// Range of pwmValueA is 0 to 65535.
(*pwmValueA) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 2
// Range of pwmValueB is 0 to 65535.
(*pwmValueB) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 3
// Range of pwmValueC is 0 to 65535.
(*pwmValueC) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// The PWM (pulse width) command for ESC with CAN ID 4
// Range of pwmValueD is 0 to 65535.
(*pwmValueD) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_CommandMultipleESCsPacket
/*!
* \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());
}// encodeESC_DisablePacket
/*!
* \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
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_DISABLE_A)
return 0;
// This value must be set for the command to be accepted
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_DISABLE_B)
return 0;
return 1;
}// decodeESC_DisablePacket
/*!
* \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());
}// encodeESC_EnablePacket
/*!
* \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
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_ENABLE_A)
return 0;
// This value must be set for the command to be included
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ESC_ENABLE_B)
return 0;
return 1;
}// decodeESC_EnablePacket
/*!
* \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
// Range of pwmCommand is 0 to 65535.
uint16ToBeBytes(pwmCommand, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_PWMCommandPacketID());
}// encodeESC_PWMCommandPacket
/*!
* \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
// Range of pwmCommand is 0 to 65535.
(*pwmCommand) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_PWMCommandPacket
/*!
* \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
// Range of rpmCommand is 0 to 65535.
uint16ToBeBytes(rpmCommand, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_RPMCommandPacketID());
}// encodeESC_RPMCommandPacket
/*!
* \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
// Range of rpmCommand is 0 to 65535.
(*rpmCommand) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_RPMCommandPacket
/*!
* \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 three bits are used for debugging and should be ignored for general use.
* \param status is ESC status 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, uint16_t command, uint16_t rpm)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Set to 1 to indicate a Gen-2 ESC
_pg_data[_pg_byteindex] = (uint8_t)1 << 7;
// Reserved for future use
// 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.
// Range of mode is 0 to 15.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(mode, 15);
_pg_byteindex += 1; // close bit field
// ESC status bits
encodeESC_StatusBits_t(_pg_data, &_pg_byteindex, status);
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
// Range of command is 0 to 65535.
uint16ToBeBytes(command, _pg_data, &_pg_byteindex);
// Motor speed
// Range of rpm is 0 to 65535.
uint16ToBeBytes(rpm, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusAPacketID());
}// encodeESC_StatusAPacket
/*!
* \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 three bits are used for debugging and should be ignored for general use.
* \param status receives ESC status 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, uint16_t* command, uint16_t* rpm)
{
unsigned int _pg_tempbitfield = 0;
int _pg_byteindex = 0;
const uint8_t* _pg_data = getESCVelocityPacketDataConst(_pg_pkt);
int _pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_StatusAPacketID())
return 0;
if(_pg_numbytes < getESC_StatusAMinDataLength())
return 0;
// Set to 1 to indicate a Gen-2 ESC
_pg_tempbitfield = (_pg_data[_pg_byteindex] >> 7);
// Decoded value must be 1
if(_pg_tempbitfield != 1)
return 0;
// Reserved for future use
// 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.
// Range of mode is 0 to 15.
(*mode) = ((_pg_data[_pg_byteindex]) & 0xF);
_pg_byteindex += 1; // close bit field
// ESC status bits
if(decodeESC_StatusBits_t(_pg_data, &_pg_byteindex, status) == 0)
return 0;
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
// Range of command is 0 to 65535.
(*command) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Motor speed
// Range of rpm is 0 to 65535.
(*rpm) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_StatusAPacket
/*!
* \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 Logic 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
// Range of voltage is 0 to 65535.
uint16ToBeBytes(voltage, _pg_data, &_pg_byteindex);
// ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
// Range of current is -32768 to 32767.
int16ToBeBytes(current, _pg_data, &_pg_byteindex);
// ESC Motor Duty Cycle
// Range of dutyCycle is 0 to 65535.
uint16ToBeBytes(dutyCycle, _pg_data, &_pg_byteindex);
// ESC Logic Board Temperature
// Range of escTemperature is -128 to 127.
int8ToBytes(escTemperature, _pg_data, &_pg_byteindex);
// ESC Motor Temperature
// Range of motorTemperature is 0 to 255.
uint8ToBytes(motorTemperature, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusBPacketID());
}// encodeESC_StatusBPacket
/*!
* \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 Logic 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
// Range of voltage is 0 to 65535.
(*voltage) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
// Range of current is -32768 to 32767.
(*current) = int16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Motor Duty Cycle
// Range of dutyCycle is 0 to 65535.
(*dutyCycle) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// ESC Logic Board Temperature
// Range of escTemperature is -128 to 127.
(*escTemperature) = int8FromBytes(_pg_data, &_pg_byteindex);
// ESC Motor Temperature
// Range of motorTemperature is 0 to 255.
(*motorTemperature) = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_StatusBPacket
/*!
* \brief Create the ESC_StatusC packet
*
* ESC Status C telemetry packet transmitted by the ESC at regular intervals
* (reserved for future use)
* \param _pg_pkt points to the packet which will be created by this function
* \param fetTemperature is ESC Phase Board Temperature
* \param pwmFrequency is Current motor PWM frequency (10 Hz per bit)
* \param timingAdvance is Current timing advance (0.1 degree per bit)
*/
void encodeESC_StatusCPacket(void* _pg_pkt, float fetTemperature, uint16_t pwmFrequency, uint16_t timingAdvance)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Reserved for future use
int16ToBeBytes((int16_t)(0), _pg_data, &_pg_byteindex);
// ESC Phase Board Temperature
// Range of fetTemperature is -50.0f to 205.0f.
float32ScaledTo1UnsignedBytes(fetTemperature, _pg_data, &_pg_byteindex, -50.0f, 1.0f);
// Current motor PWM frequency (10 Hz per bit)
// Range of pwmFrequency is 0 to 65535.
uint16ToBeBytes(pwmFrequency, _pg_data, &_pg_byteindex);
// Current timing advance (0.1 degree per bit)
// Range of timingAdvance is 0 to 65535.
uint16ToBeBytes(timingAdvance, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_StatusCPacketID());
}// encodeESC_StatusCPacket
/*!
* \brief Decode the ESC_StatusC packet
*
* ESC Status C telemetry packet transmitted by the ESC at regular intervals
* (reserved for future use)
* \param _pg_pkt points to the packet being decoded by this function
* \param fetTemperature receives ESC Phase Board Temperature
* \param pwmFrequency receives Current motor PWM frequency (10 Hz per bit)
* \param timingAdvance receives Current timing advance (0.1 degree per bit)
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_StatusCPacket(const void* _pg_pkt, float* fetTemperature, uint16_t* pwmFrequency, uint16_t* timingAdvance)
{
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_StatusCPacketID())
return 0;
if(_pg_numbytes < getESC_StatusCMinDataLength())
return 0;
// Reserved for future use
_pg_byteindex += 2;
// ESC Phase Board Temperature
// Range of fetTemperature is -50.0f to 205.0f.
(*fetTemperature) = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, -50.0f, 1.0f/1.0f);
// Current motor PWM frequency (10 Hz per bit)
// Range of pwmFrequency is 0 to 65535.
(*pwmFrequency) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Current timing advance (0.1 degree per bit)
// Range of timingAdvance is 0 to 65535.
(*timingAdvance) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_StatusCPacket
/*!
* \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
// Range of xAcc is -32768 to 32767.
int16ToBeBytes(xAcc, _pg_data, &_pg_byteindex);
// Y axis acceleration value
// Range of yAcc is -32768 to 32767.
int16ToBeBytes(yAcc, _pg_data, &_pg_byteindex);
// Z axis acceleration value
// Range of zAcc is -32768 to 32767.
int16ToBeBytes(zAcc, _pg_data, &_pg_byteindex);
// Accelerometer full-scale range
// Range of fullscale is 0 to 255.
uint8ToBytes(fullscale, _pg_data, &_pg_byteindex);
// Accelerometer measurement resolution, in 'bits'.
// Range of resolution is 0 to 255.
uint8ToBytes(resolution, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AccelerometerPacketID());
}// encodeESC_AccelerometerPacket
/*!
* \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
// Range of xAcc is -32768 to 32767.
(*xAcc) = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Y axis acceleration value
// Range of yAcc is -32768 to 32767.
(*yAcc) = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Z axis acceleration value
// Range of zAcc is -32768 to 32767.
(*zAcc) = int16FromBeBytes(_pg_data, &_pg_byteindex);
// Accelerometer full-scale range
// Range of fullscale is 0 to 255.
(*fullscale) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Accelerometer measurement resolution, in 'bits'.
// Range of resolution is 0 to 255.
(*resolution) = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_AccelerometerPacket
/*!
* \brief Create the ESC_WarningErrorStatus packet
*
* Warning and error status 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_WarningErrorStatusPacketStructure(void* _pg_pkt, const ESC_WarningErrorStatus_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
encodeESC_WarningBits_t(_pg_data, &_pg_byteindex, &_pg_user->warnings);
encodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->errors);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_WarningErrorStatusPacketID());
}// encodeESC_WarningErrorStatusPacketStructure
/*!
* \brief Decode the ESC_WarningErrorStatus packet
*
* Warning and error status 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_WarningErrorStatusPacketStructure(const void* _pg_pkt, ESC_WarningErrorStatus_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_WarningErrorStatusPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_WarningErrorStatusMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
if(decodeESC_WarningBits_t(_pg_data, &_pg_byteindex, &_pg_user->warnings) == 0)
return 0;
if(decodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->errors) == 0)
return 0;
return 1;
}// decodeESC_WarningErrorStatusPacketStructure
/*!
* \brief Create the ESC_WarningErrorStatus packet
*
* Warning and error status information
* \param _pg_pkt points to the packet which will be created by this function
* \param warnings is
* \param errors is
*/
void encodeESC_WarningErrorStatusPacket(void* _pg_pkt, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
encodeESC_WarningBits_t(_pg_data, &_pg_byteindex, warnings);
encodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, errors);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_WarningErrorStatusPacketID());
}// encodeESC_WarningErrorStatusPacket
/*!
* \brief Decode the ESC_WarningErrorStatus packet
*
* Warning and error status information
* \param _pg_pkt points to the packet being decoded by this function
* \param warnings receives
* \param errors receives
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_WarningErrorStatusPacket(const void* _pg_pkt, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors)
{
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_WarningErrorStatusPacketID())
return 0;
if(_pg_numbytes < getESC_WarningErrorStatusMinDataLength())
return 0;
if(decodeESC_WarningBits_t(_pg_data, &_pg_byteindex, warnings) == 0)
return 0;
if(decodeESC_ErrorBits_t(_pg_data, &_pg_byteindex, errors) == 0)
return 0;
return 1;
}// decodeESC_WarningErrorStatusPacket
/*!
* \brief Create the ESC_MotorStatusFlags packet
*
* Motor status flags
* \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_MotorStatusFlagsPacketStructure(void* _pg_pkt, const ESC_MotorStatusFlags_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Cause of most recent standby event
// Range of standbyCause is 0 to 65535.
uint16ToBeBytes(_pg_user->standbyCause, _pg_data, &_pg_byteindex);
// Cause of most recent disable event
// Range of disableCause is 0 to 65535.
uint16ToBeBytes(_pg_user->disableCause, _pg_data, &_pg_byteindex);
// Cause of most recent motor-stop event
// Range of offCause is 0 to 65535.
uint16ToBeBytes(_pg_user->offCause, _pg_data, &_pg_byteindex);
// Cause of most recent failed-start
// Range of failedStartCause is 0 to 65535.
uint16ToBeBytes(_pg_user->failedStartCause, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_MotorStatusFlagsPacketID());
}// encodeESC_MotorStatusFlagsPacketStructure
/*!
* \brief Decode the ESC_MotorStatusFlags packet
*
* Motor status flags
* \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_MotorStatusFlagsPacketStructure(const void* _pg_pkt, ESC_MotorStatusFlags_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_MotorStatusFlagsPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_MotorStatusFlagsMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// Cause of most recent standby event
// Range of standbyCause is 0 to 65535.
_pg_user->standbyCause = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Cause of most recent disable event
// Range of disableCause is 0 to 65535.
_pg_user->disableCause = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Cause of most recent motor-stop event
// Range of offCause is 0 to 65535.
_pg_user->offCause = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Cause of most recent failed-start
// Range of failedStartCause is 0 to 65535.
_pg_user->failedStartCause = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_MotorStatusFlagsPacketStructure
/*!
* \brief Create the ESC_MotorStatusFlags packet
*
* Motor status flags
* \param _pg_pkt points to the packet which will be created by this function
* \param standbyCause is Cause of most recent standby event
* \param disableCause is Cause of most recent disable event
* \param offCause is Cause of most recent motor-stop event
* \param failedStartCause is Cause of most recent failed-start
*/
void encodeESC_MotorStatusFlagsPacket(void* _pg_pkt, uint16_t standbyCause, uint16_t disableCause, uint16_t offCause, uint16_t failedStartCause)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Cause of most recent standby event
// Range of standbyCause is 0 to 65535.
uint16ToBeBytes(standbyCause, _pg_data, &_pg_byteindex);
// Cause of most recent disable event
// Range of disableCause is 0 to 65535.
uint16ToBeBytes(disableCause, _pg_data, &_pg_byteindex);
// Cause of most recent motor-stop event
// Range of offCause is 0 to 65535.
uint16ToBeBytes(offCause, _pg_data, &_pg_byteindex);
// Cause of most recent failed-start
// Range of failedStartCause is 0 to 65535.
uint16ToBeBytes(failedStartCause, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_MotorStatusFlagsPacketID());
}// encodeESC_MotorStatusFlagsPacket
/*!
* \brief Decode the ESC_MotorStatusFlags packet
*
* Motor status flags
* \param _pg_pkt points to the packet being decoded by this function
* \param standbyCause receives Cause of most recent standby event
* \param disableCause receives Cause of most recent disable event
* \param offCause receives Cause of most recent motor-stop event
* \param failedStartCause receives Cause of most recent failed-start
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_MotorStatusFlagsPacket(const void* _pg_pkt, uint16_t* standbyCause, uint16_t* disableCause, uint16_t* offCause, uint16_t* failedStartCause)
{
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_MotorStatusFlagsPacketID())
return 0;
if(_pg_numbytes < getESC_MotorStatusFlagsMinDataLength())
return 0;
// Cause of most recent standby event
// Range of standbyCause is 0 to 65535.
(*standbyCause) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Cause of most recent disable event
// Range of disableCause is 0 to 65535.
(*disableCause) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Cause of most recent motor-stop event
// Range of offCause is 0 to 65535.
(*offCause) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Cause of most recent failed-start
// Range of failedStartCause is 0 to 65535.
(*failedStartCause) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_MotorStatusFlagsPacket
/*!
* \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 (OTP - not configurable by user)
// Range of HardwareRevision is 0 to 255.
uint8ToBytes(_pg_user->HardwareRevision, _pg_data, &_pg_byteindex);
// ESC model (OTP - not configurable by user)
// Range of Model is 0 to 255.
uint8ToBytes(_pg_user->Model, _pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
// Range of SerialNumber is 0 to 65535.
uint16ToBeBytes(_pg_user->SerialNumber, _pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
// Range of UserIDA is 0 to 65535.
uint16ToBeBytes(_pg_user->UserIDA, _pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
// Range of UserIDB is 0 to 65535.
uint16ToBeBytes(_pg_user->UserIDB, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AddressPacketID());
}// encodeESC_AddressPacketStructure
/*!
* \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 (OTP - not configurable by user)
// Range of HardwareRevision is 0 to 255.
_pg_user->HardwareRevision = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC model (OTP - not configurable by user)
// Range of Model is 0 to 255.
_pg_user->Model = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
// Range of SerialNumber is 0 to 65535.
_pg_user->SerialNumber = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
// Range of UserIDA is 0 to 65535.
_pg_user->UserIDA = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
// Range of UserIDB is 0 to 65535.
_pg_user->UserIDB = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_AddressPacketStructure
/*!
* \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 (OTP - not configurable by user)
* \param Model is ESC model (OTP - not configurable by user)
* \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, uint8_t Model, uint16_t SerialNumber, uint16_t UserIDA, uint16_t UserIDB)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// ESC hardware revision (OTP - not configurable by user)
// Range of HardwareRevision is 0 to 255.
uint8ToBytes(HardwareRevision, _pg_data, &_pg_byteindex);
// ESC model (OTP - not configurable by user)
// Range of Model is 0 to 255.
uint8ToBytes(Model, _pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
// Range of SerialNumber is 0 to 65535.
uint16ToBeBytes(SerialNumber, _pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
// Range of UserIDA is 0 to 65535.
uint16ToBeBytes(UserIDA, _pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
// Range of UserIDB is 0 to 65535.
uint16ToBeBytes(UserIDB, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_AddressPacketID());
}// encodeESC_AddressPacket
/*!
* \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 (OTP - not configurable by user)
* \param Model receives ESC model (OTP - not configurable by user)
* \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, uint8_t* Model, uint16_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 (OTP - not configurable by user)
// Range of HardwareRevision is 0 to 255.
(*HardwareRevision) = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC model (OTP - not configurable by user)
// Range of Model is 0 to 255.
(*Model) = uint8FromBytes(_pg_data, &_pg_byteindex);
// ESC Serial Number (OTP - not configurable by user)
// Range of SerialNumber is 0 to 65535.
(*SerialNumber) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value A - user can set this value to any value
// Range of UserIDA is 0 to 65535.
(*UserIDA) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// User ID Value B - user can set this value to any value
// Range of UserIDB is 0 to 65535.
(*UserIDB) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_AddressPacket
/*!
* \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
// Range of ESCTitle is 0 to 255.
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());
}// encodeESC_TitlePacket
/*!
* \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
// Range of ESCTitle is 0 to 255.
for(_pg_i = 0; _pg_i < 8; _pg_i++)
ESCTitle[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_TitlePacket
/*!
* \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
// Range of versionMajor is 0 to 255.
uint8ToBytes(_pg_user->versionMajor, _pg_data, &_pg_byteindex);
// Minor firmware version numner
// Range of versionMinor is 0 to 255.
uint8ToBytes(_pg_user->versionMinor, _pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
// Range of versionDay is 0 to 255.
uint8ToBytes(_pg_user->versionDay, _pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
// Range of versionMonth is 0 to 255.
uint8ToBytes(_pg_user->versionMonth, _pg_data, &_pg_byteindex);
// Firmware release date, year
// Range of versionYear is 0 to 65535.
uint16ToBeBytes(_pg_user->versionYear, _pg_data, &_pg_byteindex);
// Firmware checksum
// Range of firmwareChecksum is 0 to 65535.
uint16ToBeBytes(_pg_user->firmwareChecksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_FirmwarePacketID());
}// encodeESC_FirmwarePacketStructure
/*!
* \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
// Range of versionMajor is 0 to 255.
_pg_user->versionMajor = uint8FromBytes(_pg_data, &_pg_byteindex);
// Minor firmware version numner
// Range of versionMinor is 0 to 255.
_pg_user->versionMinor = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
// Range of versionDay is 0 to 255.
_pg_user->versionDay = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
// Range of versionMonth is 0 to 255.
_pg_user->versionMonth = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, year
// Range of versionYear is 0 to 65535.
_pg_user->versionYear = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Firmware checksum
// Range of firmwareChecksum is 0 to 65535.
_pg_user->firmwareChecksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_FirmwarePacketStructure
/*!
* \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
// Range of versionMajor is 0 to 255.
uint8ToBytes(versionMajor, _pg_data, &_pg_byteindex);
// Minor firmware version numner
// Range of versionMinor is 0 to 255.
uint8ToBytes(versionMinor, _pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
// Range of versionDay is 0 to 255.
uint8ToBytes(versionDay, _pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
// Range of versionMonth is 0 to 255.
uint8ToBytes(versionMonth, _pg_data, &_pg_byteindex);
// Firmware release date, year
// Range of versionYear is 0 to 65535.
uint16ToBeBytes(versionYear, _pg_data, &_pg_byteindex);
// Firmware checksum
// Range of firmwareChecksum is 0 to 65535.
uint16ToBeBytes(firmwareChecksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_FirmwarePacketID());
}// encodeESC_FirmwarePacket
/*!
* \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
// Range of versionMajor is 0 to 255.
(*versionMajor) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Minor firmware version numner
// Range of versionMinor is 0 to 255.
(*versionMinor) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, day-of-month
// Range of versionDay is 0 to 255.
(*versionDay) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release data, month-of-year
// Range of versionMonth is 0 to 255.
(*versionMonth) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Firmware release date, year
// Range of versionYear is 0 to 65535.
(*versionYear) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Firmware checksum
// Range of firmwareChecksum is 0 to 65535.
(*firmwareChecksum) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_FirmwarePacket
/*!
* \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
// Range of millisecondsSinceReset is 0 to 4294967295.
uint32ToBeBytes(_pg_user->millisecondsSinceReset, _pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
// Range of powerCycles is 0 to 65535.
uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
// Range of resetCode is 0 to 255.
uint8ToBytes(_pg_user->resetCode, _pg_data, &_pg_byteindex);
// Processor usage
// Range of cpuOccupancy is 0 to 255.
uint8ToBytes(_pg_user->cpuOccupancy, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SystemInfoPacketID());
}// encodeESC_SystemInfoPacketStructure
/*!
* \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
// Range of millisecondsSinceReset is 0 to 4294967295.
_pg_user->millisecondsSinceReset = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
// Range of powerCycles is 0 to 65535.
_pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
// Range of resetCode is 0 to 255.
_pg_user->resetCode = uint8FromBytes(_pg_data, &_pg_byteindex);
// Processor usage
// Range of cpuOccupancy is 0 to 255.
_pg_user->cpuOccupancy = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_SystemInfoPacketStructure
/*!
* \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
// Range of millisecondsSinceReset is 0 to 4294967295.
uint32ToBeBytes(millisecondsSinceReset, _pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
// Range of powerCycles is 0 to 65535.
uint16ToBeBytes(powerCycles, _pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
// Range of resetCode is 0 to 255.
uint8ToBytes(resetCode, _pg_data, &_pg_byteindex);
// Processor usage
// Range of cpuOccupancy is 0 to 255.
uint8ToBytes(cpuOccupancy, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SystemInfoPacketID());
}// encodeESC_SystemInfoPacket
/*!
* \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
// Range of millisecondsSinceReset is 0 to 4294967295.
(*millisecondsSinceReset) = uint32FromBeBytes(_pg_data, &_pg_byteindex);
// Number of power cycle events that the ESC has experienced
// Range of powerCycles is 0 to 65535.
(*powerCycles) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Processor RESET code for debug purposes
// Range of resetCode is 0 to 255.
(*resetCode) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Processor usage
// Range of cpuOccupancy is 0 to 255.
(*cpuOccupancy) = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_SystemInfoPacket
/*!
* \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());
}// encodeESC_TelemetrySettingsPacket
/*!
* \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;
}// decodeESC_TelemetrySettingsPacket
/*!
* \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;
// Set if the ESC settings are locked
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->settingsLocked == true) ? 1 : 0) << 7;
// Version of EEPROM data
// Range of version is 0 to 127.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->version, 127);
_pg_byteindex += 1; // close bit field
// Size of settings data
// Range of size is 0 to 65535.
uint16ToBeBytes(_pg_user->size, _pg_data, &_pg_byteindex);
// Settings checksum
// Range of checksum is 0 to 65535.
uint16ToBeBytes(_pg_user->checksum, _pg_data, &_pg_byteindex);
// Validated settings checksum
// Range of validatedChecksum is 0 to 65535.
uint16ToBeBytes(_pg_user->validatedChecksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_EEPROMSettingsPacketID());
}// encodeESC_EEPROMSettingsPacketStructure
/*!
* \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);
// this packet has default fields, make sure they are set
_pg_user->validatedChecksum = 0;
// Set if the ESC settings are locked
_pg_user->settingsLocked = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// Version of EEPROM data
// Range of version is 0 to 127.
_pg_user->version = ((_pg_data[_pg_byteindex]) & 0x7F);
_pg_byteindex += 1; // close bit field
// Size of settings data
// Range of size is 0 to 65535.
_pg_user->size = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Settings checksum
// Range of checksum is 0 to 65535.
_pg_user->checksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Validated settings checksum
// Range of validatedChecksum is 0 to 65535.
_pg_user->validatedChecksum = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_EEPROMSettingsPacketStructure
/*!
* \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 settingsLocked is Set if the ESC settings are locked
* \param version is Version of EEPROM data
* \param size is Size of settings data
* \param checksum is Settings checksum
* \param validatedChecksum is Validated settings checksum
*/
void encodeESC_EEPROMSettingsPacket(void* _pg_pkt, bool settingsLocked, uint8_t version, uint16_t size, uint16_t checksum, uint16_t validatedChecksum)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Set if the ESC settings are locked
_pg_data[_pg_byteindex] = (uint8_t)((settingsLocked == true) ? 1 : 0) << 7;
// Version of EEPROM data
// Range of version is 0 to 127.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(version, 127);
_pg_byteindex += 1; // close bit field
// Size of settings data
// Range of size is 0 to 65535.
uint16ToBeBytes(size, _pg_data, &_pg_byteindex);
// Settings checksum
// Range of checksum is 0 to 65535.
uint16ToBeBytes(checksum, _pg_data, &_pg_byteindex);
// Validated settings checksum
// Range of validatedChecksum is 0 to 65535.
uint16ToBeBytes(validatedChecksum, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_EEPROMSettingsPacketID());
}// encodeESC_EEPROMSettingsPacket
/*!
* \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 settingsLocked receives Set if the ESC settings are locked
* \param version receives Version of EEPROM data
* \param size receives Size of settings data
* \param checksum receives Settings checksum
* \param validatedChecksum receives Validated settings checksum
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_EEPROMSettingsPacket(const void* _pg_pkt, bool* settingsLocked, uint8_t* version, uint16_t* size, uint16_t* checksum, uint16_t* validatedChecksum)
{
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;
// this packet has default fields, make sure they are set
(*validatedChecksum) = 0;
// Set if the ESC settings are locked
(*settingsLocked) = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// Version of EEPROM data
// Range of version is 0 to 127.
(*version) = ((_pg_data[_pg_byteindex]) & 0x7F);
_pg_byteindex += 1; // close bit field
// Size of settings data
// Range of size is 0 to 65535.
(*size) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// Settings checksum
// Range of checksum is 0 to 65535.
(*checksum) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Validated settings checksum
// Range of validatedChecksum is 0 to 65535.
(*validatedChecksum) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_EEPROMSettingsPacket
/*!
* \brief Create the ESC_TelltaleValues packet
*
* ESC telltales
* \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_TelltaleValuesPacketStructure(void* _pg_pkt, const ESC_TelltaleValues_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Maximum recorded internal temperature
// Range of maxTemperature is 0 to 255.
uint8ToBytes(_pg_user->maxTemperature, _pg_data, &_pg_byteindex);
// Maximum recorded MOSFET temperature
// Range of maxFetTemperature is 0 to 255.
uint8ToBytes(_pg_user->maxFetTemperature, _pg_data, &_pg_byteindex);
// Maximum recorded motor temperature
// Range of maxMotorTemperature is 0 to 255.
uint8ToBytes(_pg_user->maxMotorTemperature, _pg_data, &_pg_byteindex);
// Maximum recorded battery voltage
// Range of maxRippleVoltage is 0 to 255.
uint8ToBytes(_pg_user->maxRippleVoltage, _pg_data, &_pg_byteindex);
// Maximum recorded battery current
// Range of maxBatteryCurrent is -3276.7f to 3276.7f.
float32ScaledTo2SignedBeBytes(_pg_user->maxBatteryCurrent, _pg_data, &_pg_byteindex, 10.0f);
// Maximum recorded regen current
// Range of maxRegenCurrent is -3276.7f to 3276.7f.
float32ScaledTo2SignedBeBytes(_pg_user->maxRegenCurrent, _pg_data, &_pg_byteindex, 10.0f);
// Number of successful motor start events
// Range of totalStarts is 0 to 65535.
uint16ToBeBytes(_pg_user->totalStarts, _pg_data, &_pg_byteindex);
// Number of failed motor start events
// Range of failedStarts is 0 to 65535.
uint16ToBeBytes(_pg_user->failedStarts, _pg_data, &_pg_byteindex);
// ESC run time
// Range of escRunTime is 0 to 4294967295.
uint32ToBeBytes(_pg_user->escRunTime, _pg_data, &_pg_byteindex);
// Motor run time
// Range of motorRunTime is 0 to 4294967295.
uint32ToBeBytes(_pg_user->motorRunTime, _pg_data, &_pg_byteindex);
// Number of recorded motor desync events
// Range of desyncEvents is 0 to 4294967295.
uint32ToBeBytes(_pg_user->desyncEvents, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_TelltaleValuesPacketID());
}// encodeESC_TelltaleValuesPacketStructure
/*!
* \brief Decode the ESC_TelltaleValues packet
*
* ESC telltales
* \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_TelltaleValuesPacketStructure(const void* _pg_pkt, ESC_TelltaleValues_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_TelltaleValuesPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_TelltaleValuesMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// this packet has default fields, make sure they are set
_pg_user->maxRippleVoltage = 0;
_pg_user->maxBatteryCurrent = 0;
_pg_user->maxRegenCurrent = 0;
_pg_user->totalStarts = 0;
_pg_user->failedStarts = 0;
_pg_user->escRunTime = 0;
_pg_user->motorRunTime = 0;
_pg_user->desyncEvents = 0;
// Maximum recorded internal temperature
// Range of maxTemperature is 0 to 255.
_pg_user->maxTemperature = uint8FromBytes(_pg_data, &_pg_byteindex);
// Maximum recorded MOSFET temperature
// Range of maxFetTemperature is 0 to 255.
_pg_user->maxFetTemperature = uint8FromBytes(_pg_data, &_pg_byteindex);
// Maximum recorded motor temperature
// Range of maxMotorTemperature is 0 to 255.
_pg_user->maxMotorTemperature = uint8FromBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 1 > _pg_numbytes)
return 1;
// Maximum recorded battery voltage
// Range of maxRippleVoltage is 0 to 255.
_pg_user->maxRippleVoltage = uint8FromBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Maximum recorded battery current
// Range of maxBatteryCurrent is -3276.7f to 3276.7f.
_pg_user->maxBatteryCurrent = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Maximum recorded regen current
// Range of maxRegenCurrent is -3276.7f to 3276.7f.
_pg_user->maxRegenCurrent = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Number of successful motor start events
// Range of totalStarts is 0 to 65535.
_pg_user->totalStarts = uint16FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Number of failed motor start events
// Range of failedStarts is 0 to 65535.
_pg_user->failedStarts = uint16FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 4 > _pg_numbytes)
return 1;
// ESC run time
// Range of escRunTime is 0 to 4294967295.
_pg_user->escRunTime = uint32FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 4 > _pg_numbytes)
return 1;
// Motor run time
// Range of motorRunTime is 0 to 4294967295.
_pg_user->motorRunTime = uint32FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 4 > _pg_numbytes)
return 1;
// Number of recorded motor desync events
// Range of desyncEvents is 0 to 4294967295.
_pg_user->desyncEvents = uint32FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_TelltaleValuesPacketStructure
/*!
* \brief Create the ESC_TelltaleValues packet
*
* ESC telltales
* \param _pg_pkt points to the packet which will be created by this function
* \param maxTemperature is Maximum recorded internal temperature
* \param maxFetTemperature is Maximum recorded MOSFET temperature
* \param maxMotorTemperature is Maximum recorded motor temperature
* \param maxRippleVoltage is Maximum recorded battery voltage
* \param maxBatteryCurrent is Maximum recorded battery current
* \param maxRegenCurrent is Maximum recorded regen current
* \param totalStarts is Number of successful motor start events
* \param failedStarts is Number of failed motor start events
* \param escRunTime is ESC run time
* \param motorRunTime is Motor run time
* \param desyncEvents is Number of recorded motor desync events
*/
void encodeESC_TelltaleValuesPacket(void* _pg_pkt, uint8_t maxTemperature, uint8_t maxFetTemperature, uint8_t maxMotorTemperature, uint8_t maxRippleVoltage, float maxBatteryCurrent, float maxRegenCurrent, uint16_t totalStarts, uint16_t failedStarts, uint32_t escRunTime, uint32_t motorRunTime, uint32_t desyncEvents)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Maximum recorded internal temperature
// Range of maxTemperature is 0 to 255.
uint8ToBytes(maxTemperature, _pg_data, &_pg_byteindex);
// Maximum recorded MOSFET temperature
// Range of maxFetTemperature is 0 to 255.
uint8ToBytes(maxFetTemperature, _pg_data, &_pg_byteindex);
// Maximum recorded motor temperature
// Range of maxMotorTemperature is 0 to 255.
uint8ToBytes(maxMotorTemperature, _pg_data, &_pg_byteindex);
// Maximum recorded battery voltage
// Range of maxRippleVoltage is 0 to 255.
uint8ToBytes(maxRippleVoltage, _pg_data, &_pg_byteindex);
// Maximum recorded battery current
// Range of maxBatteryCurrent is -3276.7f to 3276.7f.
float32ScaledTo2SignedBeBytes(maxBatteryCurrent, _pg_data, &_pg_byteindex, 10.0f);
// Maximum recorded regen current
// Range of maxRegenCurrent is -3276.7f to 3276.7f.
float32ScaledTo2SignedBeBytes(maxRegenCurrent, _pg_data, &_pg_byteindex, 10.0f);
// Number of successful motor start events
// Range of totalStarts is 0 to 65535.
uint16ToBeBytes(totalStarts, _pg_data, &_pg_byteindex);
// Number of failed motor start events
// Range of failedStarts is 0 to 65535.
uint16ToBeBytes(failedStarts, _pg_data, &_pg_byteindex);
// ESC run time
// Range of escRunTime is 0 to 4294967295.
uint32ToBeBytes(escRunTime, _pg_data, &_pg_byteindex);
// Motor run time
// Range of motorRunTime is 0 to 4294967295.
uint32ToBeBytes(motorRunTime, _pg_data, &_pg_byteindex);
// Number of recorded motor desync events
// Range of desyncEvents is 0 to 4294967295.
uint32ToBeBytes(desyncEvents, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_TelltaleValuesPacketID());
}// encodeESC_TelltaleValuesPacket
/*!
* \brief Decode the ESC_TelltaleValues packet
*
* ESC telltales
* \param _pg_pkt points to the packet being decoded by this function
* \param maxTemperature receives Maximum recorded internal temperature
* \param maxFetTemperature receives Maximum recorded MOSFET temperature
* \param maxMotorTemperature receives Maximum recorded motor temperature
* \param maxRippleVoltage receives Maximum recorded battery voltage
* \param maxBatteryCurrent receives Maximum recorded battery current
* \param maxRegenCurrent receives Maximum recorded regen current
* \param totalStarts receives Number of successful motor start events
* \param failedStarts receives Number of failed motor start events
* \param escRunTime receives ESC run time
* \param motorRunTime receives Motor run time
* \param desyncEvents receives Number of recorded motor desync events
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_TelltaleValuesPacket(const void* _pg_pkt, uint8_t* maxTemperature, uint8_t* maxFetTemperature, uint8_t* maxMotorTemperature, uint8_t* maxRippleVoltage, float* maxBatteryCurrent, float* maxRegenCurrent, uint16_t* totalStarts, uint16_t* failedStarts, uint32_t* escRunTime, uint32_t* motorRunTime, uint32_t* desyncEvents)
{
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_TelltaleValuesPacketID())
return 0;
if(_pg_numbytes < getESC_TelltaleValuesMinDataLength())
return 0;
// this packet has default fields, make sure they are set
(*maxRippleVoltage) = 0;
(*maxBatteryCurrent) = 0;
(*maxRegenCurrent) = 0;
(*totalStarts) = 0;
(*failedStarts) = 0;
(*escRunTime) = 0;
(*motorRunTime) = 0;
(*desyncEvents) = 0;
// Maximum recorded internal temperature
// Range of maxTemperature is 0 to 255.
(*maxTemperature) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Maximum recorded MOSFET temperature
// Range of maxFetTemperature is 0 to 255.
(*maxFetTemperature) = uint8FromBytes(_pg_data, &_pg_byteindex);
// Maximum recorded motor temperature
// Range of maxMotorTemperature is 0 to 255.
(*maxMotorTemperature) = uint8FromBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 1 > _pg_numbytes)
return 1;
// Maximum recorded battery voltage
// Range of maxRippleVoltage is 0 to 255.
(*maxRippleVoltage) = uint8FromBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Maximum recorded battery current
// Range of maxBatteryCurrent is -3276.7f to 3276.7f.
(*maxBatteryCurrent) = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Maximum recorded regen current
// Range of maxRegenCurrent is -3276.7f to 3276.7f.
(*maxRegenCurrent) = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Number of successful motor start events
// Range of totalStarts is 0 to 65535.
(*totalStarts) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 2 > _pg_numbytes)
return 1;
// Number of failed motor start events
// Range of failedStarts is 0 to 65535.
(*failedStarts) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 4 > _pg_numbytes)
return 1;
// ESC run time
// Range of escRunTime is 0 to 4294967295.
(*escRunTime) = uint32FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 4 > _pg_numbytes)
return 1;
// Motor run time
// Range of motorRunTime is 0 to 4294967295.
(*motorRunTime) = uint32FromBeBytes(_pg_data, &_pg_byteindex);
if(_pg_byteindex + 4 > _pg_numbytes)
return 1;
// Number of recorded motor desync events
// Range of desyncEvents is 0 to 4294967295.
(*desyncEvents) = uint32FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_TelltaleValuesPacket
/*!
* \brief Create the ESC_GitHash packet
*
* Git commit hash for the ESC firmware
* \param _pg_pkt points to the packet which will be created by this function
* \param hash is git commit hash
*/
void encodeESC_GitHashPacket(void* _pg_pkt, const char hash[8])
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// git commit hash
stringToBytes(hash, _pg_data, &_pg_byteindex, 8, 0);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_GitHashPacketID());
}// encodeESC_GitHashPacket
/*!
* \brief Decode the ESC_GitHash packet
*
* Git commit hash for the ESC firmware
* \param _pg_pkt points to the packet being decoded by this function
* \param hash receives git commit hash
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_GitHashPacket(const void* _pg_pkt, char hash[8])
{
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_GitHashPacketID())
return 0;
if(_pg_numbytes < getESC_GitHashMinDataLength())
return 0;
// git commit hash
stringFromBytes(hash, _pg_data, &_pg_byteindex, 8, 0);
return 1;
}// decodeESC_GitHashPacket
/*!
* \brief Create the ESC_PWMInputCalibration packet
*
* PWM input calibration
* \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_PWMInputCalibrationPacketStructure(void* _pg_pkt, const ESC_PWMInputCalibration_t* _pg_user)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Protocol version (reserved for future use)
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// PWM offset compensation value
// Range of pwmOffset is -128 to 127.
int8ToBytes(_pg_user->pwmOffset, _pg_data, &_pg_byteindex);
// PWM value corresponding with 0% throttle
// Range of inputMin is 0 to 65535.
uint16ToBeBytes(_pg_user->inputMin, _pg_data, &_pg_byteindex);
// PWM value corresponding with 1000% throttle
// Range of inputMax is 0 to 65535.
uint16ToBeBytes(_pg_user->inputMax, _pg_data, &_pg_byteindex);
// PWM arming threshold
// Range of armThreshold is 0 to 65535.
uint16ToBeBytes(_pg_user->armThreshold, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_PWMInputCalibrationPacketID());
}// encodeESC_PWMInputCalibrationPacketStructure
/*!
* \brief Decode the ESC_PWMInputCalibration packet
*
* PWM input calibration
* \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_PWMInputCalibrationPacketStructure(const void* _pg_pkt, ESC_PWMInputCalibration_t* _pg_user)
{
int _pg_numbytes;
int _pg_byteindex = 0;
const uint8_t* _pg_data;
// Verify the packet identifier
if(getESCVelocityPacketID(_pg_pkt) != getESC_PWMInputCalibrationPacketID())
return 0;
// Verify the packet size
_pg_numbytes = getESCVelocityPacketSize(_pg_pkt);
if(_pg_numbytes < getESC_PWMInputCalibrationMinDataLength())
return 0;
// The raw data from the packet
_pg_data = getESCVelocityPacketDataConst(_pg_pkt);
// Protocol version (reserved for future use)
// Range of protocol is 0 to 255.
_pg_user->protocol = uint8FromBytes(_pg_data, &_pg_byteindex);
// PWM offset compensation value
// Range of pwmOffset is -128 to 127.
_pg_user->pwmOffset = int8FromBytes(_pg_data, &_pg_byteindex);
// PWM value corresponding with 0% throttle
// Range of inputMin is 0 to 65535.
_pg_user->inputMin = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// PWM value corresponding with 1000% throttle
// Range of inputMax is 0 to 65535.
_pg_user->inputMax = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// PWM arming threshold
// Range of armThreshold is 0 to 65535.
_pg_user->armThreshold = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_PWMInputCalibrationPacketStructure
/*!
* \brief Create the ESC_PWMInputCalibration packet
*
* PWM input calibration
* \param _pg_pkt points to the packet which will be created by this function
* \param pwmOffset is PWM offset compensation value
* \param inputMin is PWM value corresponding with 0% throttle
* \param inputMax is PWM value corresponding with 1000% throttle
* \param armThreshold is PWM arming threshold
*/
void encodeESC_PWMInputCalibrationPacket(void* _pg_pkt, int8_t pwmOffset, uint16_t inputMin, uint16_t inputMax, uint16_t armThreshold)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Protocol version (reserved for future use)
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
// PWM offset compensation value
// Range of pwmOffset is -128 to 127.
int8ToBytes(pwmOffset, _pg_data, &_pg_byteindex);
// PWM value corresponding with 0% throttle
// Range of inputMin is 0 to 65535.
uint16ToBeBytes(inputMin, _pg_data, &_pg_byteindex);
// PWM value corresponding with 1000% throttle
// Range of inputMax is 0 to 65535.
uint16ToBeBytes(inputMax, _pg_data, &_pg_byteindex);
// PWM arming threshold
// Range of armThreshold is 0 to 65535.
uint16ToBeBytes(armThreshold, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_PWMInputCalibrationPacketID());
}// encodeESC_PWMInputCalibrationPacket
/*!
* \brief Decode the ESC_PWMInputCalibration packet
*
* PWM input calibration
* \param _pg_pkt points to the packet being decoded by this function
* \param protocol receives Protocol version (reserved for future use)
* \param pwmOffset receives PWM offset compensation value
* \param inputMin receives PWM value corresponding with 0% throttle
* \param inputMax receives PWM value corresponding with 1000% throttle
* \param armThreshold receives PWM arming threshold
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_PWMInputCalibrationPacket(const void* _pg_pkt, uint8_t* protocol, int8_t* pwmOffset, uint16_t* inputMin, uint16_t* inputMax, uint16_t* armThreshold)
{
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_PWMInputCalibrationPacketID())
return 0;
if(_pg_numbytes < getESC_PWMInputCalibrationMinDataLength())
return 0;
// Protocol version (reserved for future use)
// Range of protocol is 0 to 255.
(*protocol) = uint8FromBytes(_pg_data, &_pg_byteindex);
// PWM offset compensation value
// Range of pwmOffset is -128 to 127.
(*pwmOffset) = int8FromBytes(_pg_data, &_pg_byteindex);
// PWM value corresponding with 0% throttle
// Range of inputMin is 0 to 65535.
(*inputMin) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// PWM value corresponding with 1000% throttle
// Range of inputMax is 0 to 65535.
(*inputMax) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
// PWM arming threshold
// Range of armThreshold is 0 to 65535.
(*armThreshold) = uint16FromBeBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_PWMInputCalibrationPacket
// end of ESCPackets.c