AP_PiccoloCAN: Split device functionality into separate files

This commit is contained in:
Oliver 2023-05-22 11:57:51 +10:00 committed by Andrew Tridgell
parent b3d82bdd57
commit a246cf71f3
21 changed files with 4246 additions and 1763 deletions

View File

@ -46,10 +46,6 @@
#include <AP_PiccoloCAN/piccolo_protocol/ServoProtocol.h>
#include <AP_PiccoloCAN/piccolo_protocol/ServoPackets.h>
// Protocol files for the ECU
#include <AP_PiccoloCAN/piccolo_protocol/ECUProtocol.h>
#include <AP_PiccoloCAN/piccolo_protocol/ECUPackets.h>
extern const AP_HAL::HAL& hal;
#if HAL_CANMANAGER_ENABLED
@ -250,20 +246,16 @@ void AP_PiccoloCAN::loop()
continue;
}
switch (MessageGroup(frame_id_group)) {
switch (PiccoloCAN_MessageGroup(frame_id_group)) {
// ESC messages exist in the ACTUATOR group
case MessageGroup::ACTUATOR:
case PiccoloCAN_MessageGroup::ACTUATOR:
switch (ActuatorType(frame_id_device)) {
case ActuatorType::SERVO:
if (handle_servo_message(rxFrame)) {
// Returns true if the message was successfully decoded
}
switch (PiccoloCAN_ActuatorType(frame_id_device)) {
case PiccoloCAN_ActuatorType::SERVO:
handle_servo_message(rxFrame);
break;
case ActuatorType::ESC:
if (handle_esc_message(rxFrame)) {
// Returns true if the message was successfully decoded
}
case PiccoloCAN_ActuatorType::ESC:
handle_esc_message(rxFrame);
break;
default:
// Unknown actuator type
@ -271,11 +263,9 @@ void AP_PiccoloCAN::loop()
}
break;
case MessageGroup::ECU_OUT:
case PiccoloCAN_MessageGroup::ECU_OUT:
#if AP_EFI_CURRAWONG_ECU_ENABLED
if (handle_ecu_message(rxFrame)) {
// Returns true if the message was successfully decoded
}
handle_ecu_message(rxFrame);
#endif
break;
default:
@ -342,8 +332,8 @@ void AP_PiccoloCAN::update()
SRV_Channel::Aux_servo_function_t function = SRV_Channels::channel_function(ii);
if (SRV_Channels::get_output_pwm(function, output)) {
_servo_info[ii].command = output;
_servo_info[ii].newCommand = true;
_servos[ii].command = output;
_servos[ii].newCommand = true;
}
}
}
@ -358,9 +348,8 @@ void AP_PiccoloCAN::update()
SRV_Channel::Aux_servo_function_t motor_function = SRV_Channels::get_motor_function(ii);
if (SRV_Channels::get_output_pwm(motor_function, output)) {
_esc_info[ii].command = output;
_esc_info[ii].newCommand = true;
_escs[ii].command = output;
_escs[ii].newCommand = true;
}
}
}
@ -380,26 +369,27 @@ void AP_PiccoloCAN::update()
WITH_SEMAPHORE(_telem_sem);
for (uint8_t ii = 0; ii < PICCOLO_CAN_MAX_NUM_SERVO; ii++) {
CBSServo_Info_t &servo = _servo_info[ii];
AP_PiccoloCAN_Servo &servo = _servos[ii];
if (servo.newTelemetry) {
union {
Servo_ErrorBits_t ebits;
uint8_t errors;
} err;
err.ebits = servo.statusA.errors;
err.ebits = servo.status.statusA.errors;
logger->Write_ServoStatus(
timestamp,
ii,
(float) servo.statusA.position, // Servo position (represented in microsecond units)
(float) servo.statusB.current * 0.01f, // Servo force (actually servo current, 0.01A per bit)
(float) servo.statusB.speed, // Servo speed (degrees per second)
(uint8_t) abs(servo.statusB.dutyCycle), // Servo duty cycle (absolute value as it can be +/- 100%)
servo.statusA.command,
servo.statusB.voltage*0.01,
servo.statusB.current*0.01,
servo.statusB.temperature,
servo.statusB.temperature,
servo.position(), // Servo position (represented in microsecond units)
servo.current() * 0.01f, // Servo force (actually servo current, 0.01A per bit)
servo.speed(), // Servo speed (degrees per second)
servo.dutyCycle(), // Servo duty cycle (absolute value as it can be +/- 100%)
uint16_t(servo.commandedPosition()), // Commanded position
servo.voltage(), // Servo voltage
servo.current(), // Servo current
servo.temperature(), // Servo temperature
servo.temperature(), //
err.errors
);
@ -431,18 +421,18 @@ void AP_PiccoloCAN::send_esc_telemetry_mavlink(uint8_t mav_chan)
// Calculate index within storage array
idx = (ii % 4);
VelocityESC_Info_t &esc = _esc_info[idx];
AP_PiccoloCAN_ESC &esc = _escs[idx];
// Has the ESC been heard from recently?
if (is_esc_present(ii)) {
dataAvailable = true;
// Provide the maximum ESC temperature in the telemetry stream
temperature[idx] = MAX(esc.fetTemperature, esc.escTemperature);
voltage[idx] = esc.voltage;
current[idx] = esc.current;
temperature[idx] = esc.temperature(); // Convert to C
voltage[idx] = esc.voltage() * 10; // Convert to cV
current[idx] = esc.current() * 10; // Convert to cA
totalcurrent[idx] = 0;
rpm[idx] = esc.rpm;
rpm[idx] = esc.rpm();
count[idx] = 0;
} else {
temperature[idx] = 0;
@ -471,6 +461,9 @@ void AP_PiccoloCAN::send_esc_telemetry_mavlink(uint8_t mav_chan)
case 11:
mavlink_msg_esc_telemetry_9_to_12_send((mavlink_channel_t) mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
break;
case 15:
mavlink_msg_esc_telemetry_13_to_16_send((mavlink_channel_t) mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
break;
default:
break;
}
@ -524,11 +517,11 @@ void AP_PiccoloCAN::send_servo_messages(void)
encodeServo_EnablePacket(&txFrame);
txFrame.id |= (idx + 1);
write_frame(txFrame, timeout);
} else if (_servo_info[idx].newCommand) {
} else if (_servos[idx].newCommand) {
// A new command is provided
send_cmd = true;
cmd[jj] = _servo_info[idx].command;
_servo_info[idx].newCommand = false;
cmd[jj] = _servos[idx].command;
_servos[idx].newCommand = false;
}
}
@ -595,10 +588,10 @@ void AP_PiccoloCAN::send_esc_messages(void)
txFrame.id |= (idx + 1);
write_frame(txFrame, timeout);
}
else if (_esc_info[idx].newCommand) {
else if (_escs[idx].newCommand) {
send_cmd = true;
cmd[jj] = _esc_info[idx].command;
_esc_info[idx].newCommand = false;
cmd[jj] = _escs[idx].command;
_escs[idx].newCommand = false;
} else {
// A command of 0x7FFF is 'out of range' and will be ignored by the corresponding ESC
cmd[jj] = 0x7FFF;
@ -639,8 +632,6 @@ void AP_PiccoloCAN::send_esc_messages(void)
// interpret a servo message received over CAN
bool AP_PiccoloCAN::handle_servo_message(AP_HAL::CANFrame &frame)
{
uint64_t timestamp = AP_HAL::micros64();
// The servo address is the lower byte of the frame ID
uint8_t addr = frame.id & 0xFF;
@ -657,44 +648,14 @@ bool AP_PiccoloCAN::handle_servo_message(AP_HAL::CANFrame &frame)
return false;
}
CBSServo_Info_t &servo = _servo_info[addr];
bool result = true;
// Throw the incoming packet against each decoding routine
if (decodeServo_StatusAPacketStructure(&frame, &servo.statusA)) {
servo.newTelemetry = true;
} else if (decodeServo_StatusBPacketStructure(&frame, &servo.statusB)) {
servo.newTelemetry = true;
} else if (decodeServo_FirmwarePacketStructure(&frame, &servo.firmware)) {
// TODO
} else if (decodeServo_AddressPacketStructure(&frame, &servo.address)) {
// TODO
} else if (decodeServo_SettingsInfoPacketStructure(&frame, &servo.settings)) {
// TODO
} else if (decodeServo_TelemetryConfigPacketStructure(&frame, &servo.telemetry)) {
} else {
// Incoming frame did not match any of the packet decoding routines
result = false;
}
if (result) {
// Reset the rx timestamp
servo.last_rx_msg_timestamp = timestamp;
}
return result;
// Pass the CAN frame off to the specific servo
return _servos[addr].handle_can_frame(frame);
}
// interpret an ESC message received over CAN
bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
{
bool result = true;
#if HAL_WITH_ESC_TELEM
uint64_t timestamp = AP_HAL::micros64();
// The ESC address is the lower byte of the frame ID
uint8_t addr = frame.id & 0xFF;
@ -711,90 +672,7 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
return false;
}
VelocityESC_Info_t &esc = _esc_info[addr];
/*
* The STATUS_A packet has slight variations between Gen-1 and Gen-2 ESCs.
* We can differentiate between the different versions,
* and coerce the "legacy" values into the modern values
* Legacy STATUS_A packet variables
*/
ESC_LegacyStatusBits_t legacyStatus;
ESC_LegacyWarningBits_t legacyWarnings;
ESC_LegacyErrorBits_t legacyErrors;
// Throw the packet against each decoding routine
if (decodeESC_StatusAPacket(&frame, &esc.mode, &esc.status, &esc.setpoint, &esc.rpm)) {
esc.newTelemetry = true;
update_rpm(addr, esc.rpm);
} else if (decodeESC_LegacyStatusAPacket(&frame, &esc.mode, &legacyStatus, &legacyWarnings, &legacyErrors, &esc.setpoint, &esc.rpm)) {
// The status / warning / error bits need to be converted to modern values
// Note: Not *all* of the modern status bits are available in the Gen-1 packet
esc.status.hwInhibit = legacyStatus.hwInhibit;
esc.status.swInhibit = legacyStatus.swInhibit;
esc.status.afwEnabled = legacyStatus.afwEnabled;
esc.status.direction = legacyStatus.timeout;
esc.status.timeout = legacyStatus.timeout;
esc.status.starting = legacyStatus.starting;
esc.status.commandSource = legacyStatus.commandSource;
esc.status.running = legacyStatus.running;
// Copy the legacy warning information across
esc.warnings.overspeed = legacyWarnings.overspeed;
esc.warnings.overcurrent = legacyWarnings.overcurrent;
esc.warnings.escTemperature = legacyWarnings.escTemperature;
esc.warnings.motorTemperature = legacyWarnings.motorTemperature;
esc.warnings.undervoltage = legacyWarnings.undervoltage;
esc.warnings.overvoltage = legacyWarnings.overvoltage;
esc.warnings.invalidPWMsignal = legacyWarnings.invalidPWMsignal;
esc.warnings.settingsChecksum = legacyErrors.settingsChecksum;
// There are no common error bits between the Gen-1 and Gen-2 ICD
} else if (decodeESC_StatusBPacket(&frame, &esc.voltage, &esc.current, &esc.dutyCycle, &esc.escTemperature, &esc.motorTemperature)) {
AP_ESC_Telem_Backend::TelemetryData telem {};
telem.voltage = float(esc.voltage) * 0.1f;
telem.current = float(esc.current) * 0.1f;
telem.motor_temp_cdeg = int16_t(esc.motorTemperature * 100);
update_telem_data(addr, telem,
AP_ESC_Telem_Backend::TelemetryType::CURRENT
| AP_ESC_Telem_Backend::TelemetryType::VOLTAGE
| AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE);
esc.newTelemetry = true;
} else if (decodeESC_StatusCPacket(&frame, &esc.fetTemperature, &esc.pwmFrequency, &esc.timingAdvance)) {
// Use the higher reported value of 'escTemperature' and 'fetTemperature'
const int16_t escTemp = MAX(esc.fetTemperature, esc.escTemperature);
AP_ESC_Telem_Backend::TelemetryData telem {};
telem.temperature_cdeg = int16_t(escTemp * 100);
update_telem_data(addr, telem, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);
esc.newTelemetry = true;
} else if (decodeESC_WarningErrorStatusPacket(&frame, &esc.warnings, &esc.errors)) {
esc.newTelemetry = true;
} else if (decodeESC_FirmwarePacketStructure(&frame, &esc.firmware)) {
// TODO
} else if (decodeESC_AddressPacketStructure(&frame, &esc.address)) {
// TODO
} else if (decodeESC_EEPROMSettingsPacketStructure(&frame, &esc.eeprom)) {
// TODO
} else {
result = false;
}
if (result) {
// Reset the Rx timestamp
esc.last_rx_msg_timestamp = timestamp;
}
#endif // HAL_WITH_ESC_TELEM
return result;
return _escs[addr].handle_can_frame(frame);
}
#if AP_EFI_CURRAWONG_ECU_ENABLED
@ -886,22 +764,7 @@ bool AP_PiccoloCAN::is_servo_present(uint8_t chan, uint64_t timeout_ms)
return false;
}
CBSServo_Info_t &servo = _servo_info[chan];
// No messages received from this servo
if (servo.last_rx_msg_timestamp == 0) {
return false;
}
uint64_t now = AP_HAL::micros64();
uint64_t timeout_us = timeout_ms * 1000ULL;
if (now > (servo.last_rx_msg_timestamp + timeout_us)) {
return false;
}
return true;
return _servos[chan].is_connected(timeout_ms);
}
@ -914,22 +777,7 @@ bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint64_t timeout_ms)
return false;
}
VelocityESC_Info_t &esc = _esc_info[chan];
// No messages received from this ESC
if (esc.last_rx_msg_timestamp == 0) {
return false;
}
uint64_t now = AP_HAL::micros64();
uint64_t timeout_us = timeout_ms * 1000ULL;
if (now > (esc.last_rx_msg_timestamp + timeout_us)) {
return false;
}
return true;
return _escs[chan].is_connected(timeout_ms);
}
@ -947,9 +795,7 @@ bool AP_PiccoloCAN::is_servo_enabled(uint8_t chan)
return false;
}
CBSServo_Info_t &servo = _servo_info[chan];
return servo.statusA.status.enabled;
return _servos[chan].is_enabled();
}
@ -967,15 +813,7 @@ bool AP_PiccoloCAN::is_esc_enabled(uint8_t chan)
return false;
}
VelocityESC_Info_t &esc = _esc_info[chan];
if (esc.status.hwInhibit || esc.status.swInhibit) {
return false;
}
// ESC is present, and enabled
return true;
return _escs[chan].is_enabled();
}
@ -1004,9 +842,7 @@ bool AP_PiccoloCAN::pre_arm_check(char* reason, uint8_t reason_len)
return false;
}
VelocityESC_Info_t &esc = _esc_info[ii];
if (esc.status.hwInhibit) {
if (_escs[ii].is_hw_inhibited()) {
snprintf(reason, reason_len, "ESC %u is hardware inhibited", (ii + 1));
return false;
}
@ -1016,208 +852,5 @@ bool AP_PiccoloCAN::pre_arm_check(char* reason, uint8_t reason_len)
return true;
}
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getESCVelocityPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getESCVelocityPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishESCVelocityPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x07mm20dd
* - 07 = ACTUATOR group ID
* - mm = Message ID
* - 20 = ESC actuator type
* - dd = Device ID
*
* Note: The Device ID (lower 8 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) AP_PiccoloCAN::MessageGroup::ACTUATOR) << 24) | // CAN Group ID
((packetID & 0xFF) << 16) | // Message ID
(((uint8_t) AP_PiccoloCAN::ActuatorType::ESC) << 8); // Actuator type
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getESCVelocityPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getESCVelocityPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getServoPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getServoPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishServoPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x07mm20dd
* - 07 = ACTUATOR group ID
* - mm = Message ID
* - 00 = Servo actuator type
* - dd = Device ID
*
* Note: The Device ID (lower 8 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) AP_PiccoloCAN::MessageGroup::ACTUATOR) << 24) | // CAN Group ID
((packetID & 0xFF) << 16) | // Message ID
(((uint8_t) AP_PiccoloCAN::ActuatorType::SERVO) << 8); // Actuator type
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getServoPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getServoPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getECUPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getECUPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishECUPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x09mmdddd
* - 07 = ECU_IN (to and ECU) group ID
* - mm = Message ID
* - dd = Device ID
*
* Note: The Device ID (lower 16 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) AP_PiccoloCAN::MessageGroup::ECU_IN) << 24) | // CAN Group ID
((packetID & 0xFF) << 16); // Message ID
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getECUPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getECUPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}
#endif // HAL_PICCOLO_CAN_ENABLE

View File

@ -23,19 +23,12 @@
#include <AP_Param/AP_Param.h>
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>
#include "piccolo_protocol/ESCPackets.h"
#include "piccolo_protocol/LegacyESCPackets.h"
#include "piccolo_protocol/ServoPackets.h"
#include "AP_PiccoloCAN_Device.h"
#include "AP_PiccoloCAN_ESC.h"
#include "AP_PiccoloCAN_ECU.h"
#include "AP_PiccoloCAN_Servo.h"
#include <AP_EFI/AP_EFI_Currawong_ECU.h>
// maximum number of ESC allowed on CAN bus simultaneously
#define PICCOLO_CAN_MAX_NUM_ESC 16
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
#define PICCOLO_CAN_MAX_NUM_SERVO 16
#define PICCOLO_CAN_MAX_GROUP_SERVO (PICCOLO_CAN_MAX_NUM_SERVO / 4)
#ifndef HAL_PICCOLO_CAN_ENABLE
#define HAL_PICCOLO_CAN_ENABLE HAL_NUM_CAN_IFACES
@ -47,31 +40,12 @@
#define PICCOLO_MSG_RATE_HZ_MAX 500
#define PICCOLO_MSG_RATE_HZ_DEFAULT 50
#define PICCOLO_CAN_ECU_ID_DEFAULT 0
class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend
{
public:
AP_PiccoloCAN();
~AP_PiccoloCAN();
// Piccolo message groups form part of the CAN ID of each frame
enum class MessageGroup : uint8_t {
SIMULATOR = 0x00, // Simulator messages
SENSOR = 0x04, // External sensors
ACTUATOR = 0x07, // Actuators (e.g. ESC / servo)
ECU_OUT = 0x08, // Messages *from* an ECU
ECU_IN = 0x09, // Message *to* an ECU
SYSTEM = 0x19, // System messages (e.g. bootloader)
};
// Piccolo actuator types differentiate between actuator frames
enum class ActuatorType : uint8_t {
SERVO = 0x00,
ESC = 0x20,
};
/* Do not allow copies */
CLASS_NO_COPY(AP_PiccoloCAN);
@ -147,29 +121,8 @@ private:
AP_HAL::CANIface* _can_iface;
HAL_EventHandle _event_handle;
// Data structure for representing the state of a CBS servo
struct CBSServo_Info_t {
/* Telemetry data provided across multiple packets */
Servo_StatusA_t statusA;
Servo_StatusB_t statusB;
/* Servo configuration information */
Servo_Firmware_t firmware;
Servo_Address_t address;
Servo_SettingsInfo_t settings;
Servo_SystemInfo_t systemInfo;
Servo_TelemetryConfig_t telemetry;
/* Internal state information */
int16_t command; //! Raw command to send to each servo
bool newCommand; //! Is the command "new"?
bool newTelemetry; //! Is there new telemetry data available?
uint64_t last_rx_msg_timestamp = 0; //! Time of most recently received message
} _servo_info[PICCOLO_CAN_MAX_NUM_SERVO];
AP_PiccoloCAN_Servo _servos[PICCOLO_CAN_MAX_NUM_SERVO];
AP_PiccoloCAN_ESC _escs[PICCOLO_CAN_MAX_NUM_ESC];
// Data structure for representing the state of a Velocity ESC
struct VelocityESC_Info_t {
@ -192,23 +145,9 @@ private:
uint16_t pwmFrequency; //!< Current motor PWM frequency (10 Hz per bit)
uint16_t timingAdvance; //!< Current timing advance (0.1 degree per bit)
/* ESC status information provided in the PKT_ESC_WARNINGS_ERRORS packet */
ESC_WarningBits_t warnings; //! ESC warning information
ESC_ErrorBits_t errors; //! ESC error information
ESC_Firmware_t firmware; //! Firmware / checksum information
ESC_Address_t address; //! Serial number
ESC_EEPROMSettings_t eeprom; //! Non-volatile settings info
// Output information
int16_t command; //! Raw command to send to each ESC
bool newCommand; //! Is the command "new"?
bool newTelemetry; //! Is there new telemetry data available?
uint64_t last_rx_msg_timestamp = 0; //! Time of most recently received message
} _esc_info[PICCOLO_CAN_MAX_NUM_ESC];
} _esc_ixnfo[PICCOLO_CAN_MAX_NUM_ESC];
struct CurrawongECU_Info_t {
float command;

View File

@ -0,0 +1,68 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#pragma once
#include <stdint.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_CANManager/AP_CANManager.h>
// Piccolo message groups form part of the CAN ID of each frame
enum class PiccoloCAN_MessageGroup : uint8_t {
SIMULATOR = 0x00, // Simulator messages
SENSOR = 0x04, // External sensors
ACTUATOR = 0x07, // Actuators (e.g. ESC / servo)
ECU_OUT = 0x08, // Messages *from* an ECU
ECU_IN = 0x09, // Message *to* an ECU
SYSTEM = 0x19, // System messages (e.g. bootloader)
};
// Piccolo actuator types differentiate between actuator frames
enum class PiccoloCAN_ActuatorType : uint8_t {
SERVO = 0x00,
ESC = 0x20,
};
/*
* Generic PiccoloCAN device class implementation
*/
class AP_PiccoloCAN_Device
{
public:
virtual bool handle_can_frame(AP_HAL::CANFrame &frame) = 0;
// Determine if this device is "enabled" (default implementation returns false)
virtual bool is_enabled(void) const { return false; }
// Determine if this device has been seen within a specified timeframe
virtual bool is_connected(int64_t timeout_ms) const {
uint64_t now = AP_HAL::micros64();
return now < (last_msg_timestamp + (1000ULL * timeout_ms));
}
// Reset the received message timestamp
void reset_rx_timestamp() {
last_msg_timestamp = AP_HAL::micros64();
}
//! Timestamp of most recently received CAN message
uint64_t last_msg_timestamp = 0;
};

View File

@ -0,0 +1,90 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "AP_PiccoloCAN_ECU.h"
// Protocol files for the ECU
#include <AP_PiccoloCAN/piccolo_protocol/ECUProtocol.h>
#include <AP_PiccoloCAN/piccolo_protocol/ECUPackets.h>
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getECUPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getECUPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishECUPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x09mmdddd
* - 07 = ECU_IN (to and ECU) group ID
* - mm = Message ID
* - dd = Device ID
*
* Note: The Device ID (lower 16 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) PiccoloCAN_MessageGroup::ECU_IN) << 24) | // CAN Group ID
((packetID & 0xFF) << 16); // Message ID
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getECUPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getECUPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}

View File

@ -0,0 +1,35 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#pragma once
#include <AP_CANManager/AP_CANManager.h>
#include "AP_PiccoloCAN_Device.h"
#include "piccolo_protocol/ECUPackets.h"
#define PICCOLO_CAN_ECU_ID_DEFAULT 0
/*
* Class representing an individual PiccoloCAN ECU
*/
class AP_PiccoloCAN_ECU : public AP_PiccoloCAN_Device
{
public:
// TODO
};

View File

@ -0,0 +1,148 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "AP_PiccoloCAN_ESC.h"
/*
* Decode a recevied CAN frame.
* It is assumed at this point that the received frame is intended for *this* ESC
*/
bool AP_PiccoloCAN_ESC::handle_can_frame(AP_HAL::CANFrame &frame)
{
bool result = true;
// The ESC address is the lower byte of the frame ID
uint8_t addr = frame.id & 0xFF;
// Ignore any ESC with node ID of zero
if (addr == 0x00) {
return false;
}
addr -= 1;
uint8_t extended;
if (decodeESC_StatusAPacketStructure(&frame, &status.statusA)) {
newTelemetry = true;
update_rpm(addr, rpm());
} else if (decodeESC_StatusBPacketStructure(&frame, &status.statusB)) {
AP_ESC_Telem_Backend::TelemetryData telem {};
telem.voltage = voltage() * 10;
telem.current = current() * 10;
telem.motor_temp_cdeg = int16_t(motorTemperature() * 100);
telem.temperature_cdeg = int16_t(temperature() * 100);
update_telem_data(addr, telem,
AP_ESC_Telem_Backend::TelemetryType::CURRENT |
AP_ESC_Telem_Backend::TelemetryType::VOLTAGE |
AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE |
AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE);
newTelemetry = true;
} else if (decodeESC_StatusCPacketStructure(&frame, &status.statusC)) {
AP_ESC_Telem_Backend::TelemetryData telem {};
telem.temperature_cdeg = temperature() * 100;
update_telem_data(addr, telem, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);
newTelemetry = true;
} else if (decodeESC_WarningErrorStatusPacket(&frame, &status.warnings, &status.errors, &extended, &status.warnings, &status.errors)) {
newTelemetry = true;
} else if (decodeESC_FirmwarePacketStructure(&frame, &settings.firmware)) {
} else if (decodeESC_AddressPacketStructure(&frame, &settings.address)) {
} else if (decodeESC_EEPROMSettingsPacketStructure(&frame, &settings.eeprom)) {
} else {
result = false;
}
if (result) {
reset_rx_timestamp();
}
return result;
}
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getESCVelocityPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getESCVelocityPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishESCVelocityPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x07mm20dd
* - 07 = ACTUATOR group ID
* - mm = Message ID
* - 20 = ESC actuator type
* - dd = Device ID
*
* Note: The Device ID (lower 8 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) PiccoloCAN_MessageGroup::ACTUATOR) << 24) | // CAN Group ID
((packetID & 0xFF) << 16) | // Message ID
(((uint8_t) PiccoloCAN_ActuatorType::ESC) << 8); // Actuator type
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getESCVelocityPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getESCVelocityPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}

View File

@ -0,0 +1,72 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#pragma once
#include <AP_Math/AP_Math.h>
#include <AP_CANManager/AP_CANManager.h>
#include <AP_ESC_Telem/AP_ESC_Telem_Backend.h>
#include "AP_PiccoloCAN_Device.h"
#include "piccolo_protocol/ESCPackets.h"
#define PICCOLO_CAN_MAX_NUM_ESC 16
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
/*
* Class representing an individual PiccoloCAN ESC
*/
class AP_PiccoloCAN_ESC : public AP_PiccoloCAN_Device, public AP_ESC_Telem_Backend
{
public:
virtual bool handle_can_frame(AP_HAL::CANFrame &frame) override;
bool is_sw_inhibited(void) const { return status.statusA.status.swInhibit; }
bool is_hw_inhibited(void) const { return status.statusA.status.hwInhibit; }
virtual bool is_enabled(void) const override { return !is_sw_inhibited() && !is_hw_inhibited(); }
float voltage() { return (float) status.statusB.voltage * 0.01f; } // Convert to V
float current() { return (float) status.statusB.current * 0.01f; } // Convert to A
uint16_t rpm() { return status.statusA.rpm; }
float temperature() { return MAX(status.statusB.escTemperature, status.statusC.fetTemperature); }
float motorTemperature() { return status.statusB.motorTemperature; }
int16_t command; //! Raw command to send to each ESC
bool newCommand; //! Is the command "new"?
bool newTelemetry; //! Is there new telemetry data available?
// Status / telemetry data
struct Status_t {
ESC_StatusA_t statusA;
ESC_StatusB_t statusB;
ESC_StatusC_t statusC;
ESC_WarningBits_t warnings;
ESC_ErrorBits_t errors;
} status;
// Settings information
struct Settings_t {
ESC_Firmware_t firmware;
ESC_Address_t address;
ESC_EEPROMSettings_t eeprom;
} settings;
};

View File

@ -0,0 +1,115 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "AP_PiccoloCAN_Servo.h"
/*
* Decode a recevied CAN frame.
* It is assumed at this point that the received frame is intended for *this* servo
*/
bool AP_PiccoloCAN_Servo::handle_can_frame(AP_HAL::CANFrame &frame)
{
bool result = true;
if (decodeServo_StatusAPacketStructure(&frame, &status.statusA)) {
newTelemetry = true;
} else if (decodeServo_StatusBPacketStructure(&frame, &status.statusB)) {
newTelemetry = true;
} else if (decodeServo_FirmwarePacketStructure(&frame, &settings.firmware)) {
} else if (decodeServo_AddressPacketStructure(&frame, &settings.address)) {
} else if (decodeServo_SettingsInfoPacketStructure(&frame, &settings.settings)) {
} else {
// Incoming frame did not match any packet decoding routine
result = false;
}
if (result) {
reset_rx_timestamp();
}
return result;
}
/* Piccolo Glue Logic
* The following functions are required by the auto-generated protogen code.
*/
//! \return the packet data pointer from the packet
uint8_t* getServoPacketData(void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getServoPacketDataConst(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (const uint8_t*) frame->data;
}
//! Complete a packet after the data have been encoded
void finishServoPacket(void* pkt, int size, uint32_t packetID)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
if (size > AP_HAL::CANFrame::MaxDataLen) {
size = AP_HAL::CANFrame::MaxDataLen;
}
frame->dlc = size;
/* Encode the CAN ID
* 0x07mm20dd
* - 07 = ACTUATOR group ID
* - mm = Message ID
* - 00 = Servo actuator type
* - dd = Device ID
*
* Note: The Device ID (lower 8 bits of the frame ID) will have to be inserted later
*/
uint32_t id = (((uint8_t) PiccoloCAN_MessageGroup::ACTUATOR) << 24) | // CAN Group ID
((packetID & 0xFF) << 16) | // Message ID
(((uint8_t) PiccoloCAN_ActuatorType::SERVO) << 8); // Actuator type
// Extended frame format
id |= AP_HAL::CANFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getServoPacketSize(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getServoPacketID(const void* pkt)
{
AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}

View File

@ -0,0 +1,65 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#pragma once
#include <AP_CANManager/AP_CANManager.h>
#include "AP_PiccoloCAN_Device.h"
#include "piccolo_protocol/ServoPackets.h"
#define PICCOLO_CAN_MAX_NUM_SERVO 16
#define PICCOLO_CAN_MAX_GROUP_SERVO (PICCOLO_CAN_MAX_NUM_SERVO / 4)
/*
* Class representing an individual PiccoloCAN servo
*/
class AP_PiccoloCAN_Servo : public AP_PiccoloCAN_Device
{
public:
virtual bool handle_can_frame(AP_HAL::CANFrame &frame) override;
virtual bool is_enabled(void) const override { return status.statusA.status.enabled; }
// Helper functions for accessing servo status data
float position() const { return (float) status.statusA.position; }
float commandedPosition() const { return (float) status.statusA.command; }
float current() const { return (float) status.statusB.current * 0.01f; }
float voltage() const { return (float) status.statusB.voltage * 0.01f; }
float speed() const { return (float) status.statusB.speed; }
uint8_t dutyCycle() const { return abs(status.statusB.dutyCycle); }
float temperature() const { return (float) status.statusB.temperature; }
int16_t command = 0;
bool newCommand = false;
bool newTelemetry = false;
// Status / telemetry data
struct Status_t {
Servo_StatusA_t statusA;
Servo_StatusB_t statusB;
} status;
// Settings information
struct Settings_t {
Servo_Firmware_t firmware;
Servo_Address_t address;
Servo_SettingsInfo_t settings;
} settings;
};

View File

@ -1,4 +1,4 @@
// ESCCommands.c was generated by ProtoGen version 3.2.a
// ESCCommands.c was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "ESCCommands.h"
@ -194,6 +194,61 @@ int decodeESC_SetUserIDBPacket(const void* _pg_pkt, uint16_t* id)
}// decodeESC_SetUserIDBPacket
/*!
* \brief Create the ESC_SetMotorDirection packet
*
* Set Motor Direction
* \param _pg_pkt points to the packet which will be created by this function
* \param direction is 0 = Motor direction is FORWARDS, 1 = Motor direction is REVERSE
*/
void encodeESC_SetMotorDirectionPacket(void* _pg_pkt, uint8_t direction)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
uint8ToBytes((uint8_t)(CMD_ESC_SET_MOTOR_DIRECTION), _pg_data, &_pg_byteindex);
// 0 = Motor direction is FORWARDS, 1 = Motor direction is REVERSE
// Range of direction is 0 to 255.
uint8ToBytes(direction, _pg_data, &_pg_byteindex);
// complete the process of creating the packet
finishESCVelocityPacket(_pg_pkt, _pg_byteindex, getESC_SetMotorDirectionPacketID());
}// encodeESC_SetMotorDirectionPacket
/*!
* \brief Decode the ESC_SetMotorDirection packet
*
* Set Motor Direction
* \param _pg_pkt points to the packet being decoded by this function
* \param direction receives 0 = Motor direction is FORWARDS, 1 = Motor direction is REVERSE
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_SetMotorDirectionPacket(const void* _pg_pkt, uint8_t* direction)
{
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_SetMotorDirectionPacketID())
return 0;
if(_pg_numbytes < getESC_SetMotorDirectionMinDataLength())
return 0;
if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) CMD_ESC_SET_MOTOR_DIRECTION)
return 0;
// 0 = Motor direction is FORWARDS, 1 = Motor direction is REVERSE
// Range of direction is 0 to 255.
(*direction) = uint8FromBytes(_pg_data, &_pg_byteindex);
return 1;
}// decodeESC_SetMotorDirectionPacket
/*!
* \brief Create the ESC_UnlockSettings packet
*

View File

@ -1,4 +1,4 @@
// ESCCommands.h was generated by ProtoGen version 3.2.a
// ESCCommands.h was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ESCCOMMANDS_H
@ -29,6 +29,7 @@ extern "C" {
* \file
*/
#include <stdint.h>
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
@ -86,6 +87,21 @@ int decodeESC_SetUserIDBPacket(const void* pkt, uint16_t* id);
//! return the maximum encoded length for the ESC_SetUserIDB packet
#define getESC_SetUserIDBMaxDataLength() (3)
//! Create the ESC_SetMotorDirection packet from parameters
void encodeESC_SetMotorDirectionPacket(void* pkt, uint8_t direction);
//! Decode the ESC_SetMotorDirection packet to parameters
int decodeESC_SetMotorDirectionPacket(const void* pkt, uint8_t* direction);
//! return the packet ID for the ESC_SetMotorDirection packet
#define getESC_SetMotorDirectionPacketID() (PKT_ESC_SYSTEM_CMD)
//! return the minimum encoded length for the ESC_SetMotorDirection packet
#define getESC_SetMotorDirectionMinDataLength() (2)
//! return the maximum encoded length for the ESC_SetMotorDirection packet
#define getESC_SetMotorDirectionMaxDataLength() (2)
//! Create the ESC_UnlockSettings packet from parameters
void encodeESC_UnlockSettingsPacket(void* pkt);

View File

@ -1,4 +1,4 @@
// ESCDefines.c was generated by ProtoGen version 3.2.a
// ESCDefines.c was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "ESCDefines.h"
@ -66,6 +66,12 @@ void encodeESC_StatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Sta
// Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->anyErrors == true) ? 1 : 0) << 6;
// Set if ESC is armed to respond to CAN commands
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->canArmed == true) ? 1 : 0) << 5;
// Set if ESC is armed to respond to PWM Input commands
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->pwmArmed == true) ? 1 : 0) << 4;
// Reserved bits for future use
// Set if the motor is spinning (even if it is not being driven)
@ -74,14 +80,23 @@ void encodeESC_StatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Sta
// Set if motor is spinning opposite to configured rotation direction
_pg_data[_pg_byteindex + 2] = (uint8_t)((_pg_user->spinningReversed == true) ? 1 : 0) << 7;
// Set if motor duty cycle is being limited due to ESC protection settings
// Set if motor duty cycle is being actively reduced due to ESC protection settings
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->foldback == true) ? 1 : 0) << 6;
// Set if the ESC is attempting to sync with the motor
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->syncing == true) ? 1 : 0) << 5;
// Set if the ESC is applying motor braking
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->braking == true) ? 1 : 0) << 4;
// Set if the motor duty cycle is being actively increased due to ESC protection settings
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->foldforward == true) ? 1 : 0) << 3;
// Reserved bits for future use
// Set if the ESC settings are locked and cannot be changed
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->settingsLocked == true) ? 1 : 0) << 1;
// Set if the ESC is in debug mode (factory use only)
_pg_data[_pg_byteindex + 2] |= (uint8_t)((_pg_user->debug == true) ? 1 : 0);
_pg_byteindex += 3; // close bit field
@ -134,6 +149,12 @@ int decodeESC_StatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Stat
// Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet
_pg_user->anyErrors = (((_pg_data[_pg_byteindex + 1] >> 6) & 0x1)) ? true : false;
// Set if ESC is armed to respond to CAN commands
_pg_user->canArmed = (((_pg_data[_pg_byteindex + 1] >> 5) & 0x1)) ? true : false;
// Set if ESC is armed to respond to PWM Input commands
_pg_user->pwmArmed = (((_pg_data[_pg_byteindex + 1] >> 4) & 0x1)) ? true : false;
// Reserved bits for future use
// Set if the motor is spinning (even if it is not being driven)
@ -142,14 +163,23 @@ int decodeESC_StatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Stat
// Set if motor is spinning opposite to configured rotation direction
_pg_user->spinningReversed = ((_pg_data[_pg_byteindex + 2] >> 7)) ? true : false;
// Set if motor duty cycle is being limited due to ESC protection settings
// Set if motor duty cycle is being actively reduced due to ESC protection settings
_pg_user->foldback = (((_pg_data[_pg_byteindex + 2] >> 6) & 0x1)) ? true : false;
// Set if the ESC is attempting to sync with the motor
_pg_user->syncing = (((_pg_data[_pg_byteindex + 2] >> 5) & 0x1)) ? true : false;
// Set if the ESC is applying motor braking
_pg_user->braking = (((_pg_data[_pg_byteindex + 2] >> 4) & 0x1)) ? true : false;
// Set if the motor duty cycle is being actively increased due to ESC protection settings
_pg_user->foldforward = (((_pg_data[_pg_byteindex + 2] >> 3) & 0x1)) ? true : false;
// Reserved bits for future use
// Set if the ESC settings are locked and cannot be changed
_pg_user->settingsLocked = (((_pg_data[_pg_byteindex + 2] >> 1) & 0x1)) ? true : false;
// Set if the ESC is in debug mode (factory use only)
_pg_user->debug = (((_pg_data[_pg_byteindex + 2]) & 0x1)) ? true : false;
_pg_byteindex += 3; // close bit field
@ -183,7 +213,7 @@ void encodeESC_WarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Wa
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overspeed == true) ? 1 : 0) << 6;
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
// Set if the ESC DC current (positive, into the motor) exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overcurrent == true) ? 1 : 0) << 5;
// Set if the internal ESC temperature is above the warning threshold
@ -222,7 +252,8 @@ void encodeESC_WarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Wa
// Settings checksum does not match programmed value
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->settingsChecksum == true) ? 1 : 0) << 1;
// Reserved for future use
// Set if the ESC's CPU usage is high
_pg_data[_pg_byteindex + 1] |= (uint8_t)((_pg_user->highCPUUsage == true) ? 1 : 0);
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -252,7 +283,7 @@ int decodeESC_WarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_War
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_user->overspeed = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
// Set if the ESC DC current (positive, into the motor) exceeds the configured warning threshold
_pg_user->overcurrent = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Set if the internal ESC temperature is above the warning threshold
@ -291,7 +322,8 @@ int decodeESC_WarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_War
// Settings checksum does not match programmed value
_pg_user->settingsChecksum = (((_pg_data[_pg_byteindex + 1] >> 1) & 0x1)) ? true : false;
// Reserved for future use
// Set if the ESC's CPU usage is high
_pg_user->highCPUUsage = (((_pg_data[_pg_byteindex + 1]) & 0x1)) ? true : false;
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -300,6 +332,74 @@ int decodeESC_WarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_War
}// decodeESC_WarningBits_t
/*!
* \brief Encode a ESC_ExtendedWarningBits_t into a byte array
*
* \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_ExtendedWarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_WarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
unsigned int _pg_tempbitfield = 0;
// Set if the ESC DC current (negative, out of the motor) exceeds the configured warning threshold
_pg_data[_pg_byteindex] = (uint8_t)((_pg_user->regenCurrent == true) ? 1 : 0) << 7;
// Set if the hall sensors are running out of specification
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->hallSensors == true) ? 1 : 0) << 6;
// Reserved for future use
// Range of reservedWarningBits is 0 to 16383.
_pg_tempbitfield = (unsigned int)limitMax(_pg_user->reservedWarningBits, 16383);
_pg_data[_pg_byteindex + 1] = (uint8_t)_pg_tempbitfield;
_pg_tempbitfield >>= 8;
_pg_data[_pg_byteindex] |= (uint8_t)_pg_tempbitfield;
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_ExtendedWarningBits_t
/*!
* \brief Decode a ESC_ExtendedWarningBits_t from a byte array
*
* \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_ExtendedWarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_WarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
unsigned int _pg_tempbitfield = 0;
// Set if the ESC DC current (negative, out of the motor) exceeds the configured warning threshold
_pg_user->regenCurrent = ((_pg_data[_pg_byteindex] >> 7)) ? true : false;
// Set if the hall sensors are running out of specification
_pg_user->hallSensors = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Reserved for future use
// Range of reservedWarningBits is 0 to 16383.
_pg_tempbitfield = (_pg_data[_pg_byteindex] & 0x3F);
_pg_tempbitfield <<= 8;
_pg_tempbitfield |= _pg_data[_pg_byteindex + 1];
_pg_user->reservedWarningBits = _pg_tempbitfield;
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_ExtendedWarningBits_t
/*!
* \brief Encode a ESC_ErrorBits_t into a byte array
*
@ -322,7 +422,7 @@ void encodeESC_ErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Erro
// Set if hall sensor error detected
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->hallSensor == true) ? 1 : 0) << 5;
// Current exceeded hard-limit
// Current exceeded hard limit
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->overcurrent == true) ? 1 : 0) << 4;
// Temperature exceeded hard-limit
@ -334,8 +434,11 @@ void encodeESC_ErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_Erro
// Motor stopped due to high demag angle
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->demag == true) ? 1 : 0) << 1;
// Reserved for future use
_pg_data[_pg_byteindex + 1] = 0;
// Phase voltage error detected
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->phaseVoltage == true) ? 1 : 0);
// Regen current exceeded hard limit
_pg_data[_pg_byteindex + 1] = (uint8_t)((_pg_user->regenCurrent == true) ? 1 : 0) << 7;
// Reserved for future use
_pg_byteindex += 2; // close bit field
@ -367,7 +470,7 @@ int decodeESC_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Error
// Set if hall sensor error detected
_pg_user->hallSensor = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Current exceeded hard-limit
// Current exceeded hard limit
_pg_user->overcurrent = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// Temperature exceeded hard-limit
@ -379,7 +482,11 @@ int decodeESC_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Error
// Motor stopped due to high demag angle
_pg_user->demag = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// Reserved for future use
// Phase voltage error detected
_pg_user->phaseVoltage = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
// Regen current exceeded hard limit
_pg_user->regenCurrent = ((_pg_data[_pg_byteindex + 1] >> 7)) ? true : false;
// Reserved for future use
_pg_byteindex += 2; // close bit field
@ -390,6 +497,49 @@ int decodeESC_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_Error
}// decodeESC_ErrorBits_t
/*!
* \brief Encode a ESC_ExtendedErrorBits_t into a byte array
*
* \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_ExtendedErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_ErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved for future use
// Range of reservedErrorBits is 0 to 255.
uint8ToBytes(_pg_user->reservedErrorBits, _pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
}// encodeESC_ExtendedErrorBits_t
/*!
* \brief Decode a ESC_ExtendedErrorBits_t from a byte array
*
* \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_ExtendedErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_ErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Reserved for future use
// Range of reservedErrorBits is 0 to 255.
_pg_user->reservedErrorBits = uint8FromBytes(_pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_ExtendedErrorBits_t
/*!
* \brief Encode a ESC_TelemetryPackets_t into a byte array
*
@ -413,8 +563,7 @@ void encodeESC_TelemetryPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const E
// If this bit is set, the STATUS_C packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->statusC == true) ? 1 : 0) << 5;
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->accelerometer == true) ? 1 : 0) << 4;
// Hidden field skipped
// If this bit is set, the STATUS_D packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->statusD == true) ? 1 : 0) << 3;
@ -457,8 +606,7 @@ int decodeESC_TelemetryPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ES
// If this bit is set, the STATUS_C packet will be transmitted at the configured rate
_pg_user->statusC = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_user->accelerometer = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
// Hidden field skipped
// If this bit is set, the STATUS_D packet will be transmitted at the configured rate
_pg_user->statusD = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
@ -498,8 +646,8 @@ void encodeESC_DebugPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_D
// Hall sensor debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->hallSensors == true) ? 1 : 0) << 6;
// Commutation debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->commutation == true) ? 1 : 0) << 5;
// Commutation A debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->commutationA == true) ? 1 : 0) << 5;
// Demag debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->demag == true) ? 1 : 0) << 4;
@ -507,11 +655,20 @@ void encodeESC_DebugPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_D
// PWM input debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->pwmInput == true) ? 1 : 0) << 3;
// Reserved for future use
_pg_byteindex += 1; // close bit field
// Commutation B debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->commutationB == true) ? 1 : 0) << 2;
// Commutation C debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->commutationC == true) ? 1 : 0) << 1;
// Direct phase sampling debug information
_pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->phaseSamples == true) ? 1 : 0);
// Starting debug information
_pg_data[_pg_byteindex + 1] = (uint8_t)((_pg_user->starting == true) ? 1 : 0) << 7;
// Reserved for future use
uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex);
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -537,8 +694,8 @@ int decodeESC_DebugPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_De
// Hall sensor debug information
_pg_user->hallSensors = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false;
// Commutation debug information
_pg_user->commutation = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Commutation A debug information
_pg_user->commutationA = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false;
// Demag debug information
_pg_user->demag = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false;
@ -546,11 +703,20 @@ int decodeESC_DebugPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_De
// PWM input debug information
_pg_user->pwmInput = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false;
// Reserved for future use
_pg_byteindex += 1; // close bit field
// Commutation B debug information
_pg_user->commutationB = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false;
// Commutation C debug information
_pg_user->commutationC = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false;
// Direct phase sampling debug information
_pg_user->phaseSamples = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false;
// Starting debug information
_pg_user->starting = ((_pg_data[_pg_byteindex + 1] >> 7)) ? true : false;
// Reserved for future use
_pg_byteindex += 1;
_pg_byteindex += 2; // close bit field
*_pg_bytecount = _pg_byteindex;
@ -558,4 +724,95 @@ int decodeESC_DebugPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_De
}// decodeESC_DebugPackets_t
/*!
* \brief Encode a ESC_ControlLoopCommon_t into a byte array
*
* \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_ControlLoopCommon_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_ControlLoopCommon_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Control loop proportional gain
// Range of Kp is 0.0f to 50.0f.
float32ScaledTo2UnsignedBeBytes(_pg_user->Kp, _pg_data, &_pg_byteindex, 0.0f, 1310.7f);
// Control loop integral gain
// Range of Ki is 0.0f to 50.0f.
float32ScaledTo2UnsignedBeBytes(_pg_user->Ki, _pg_data, &_pg_byteindex, 0.0f, 1310.7f);
// Control loop derivative
// Range of Kd is 0.0f to 50.0f.
float32ScaledTo2UnsignedBeBytes(_pg_user->Kd, _pg_data, &_pg_byteindex, 0.0f, 1310.7f);
// Control loop feed-forward gain
// Range of Kf is 0.0f to 50.0f.
float32ScaledTo2UnsignedBeBytes(_pg_user->Kf, _pg_data, &_pg_byteindex, 0.0f, 1310.7f);
// Minimum PWM limit for control loop output
// Range of minPwm is 0 to 255.
uint8ToBytes(_pg_user->minPwm, _pg_data, &_pg_byteindex);
// Maximum PWM limit for control loop output
// Range of maxPwm is 0 to 255.
uint8ToBytes(_pg_user->maxPwm, _pg_data, &_pg_byteindex);
// Reserved for future use
// Range of reserved is 0 to 255.
uint8ToBytes(_pg_user->reserved, _pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
}// encodeESC_ControlLoopCommon_t
/*!
* \brief Decode a ESC_ControlLoopCommon_t from a byte array
*
* \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_ControlLoopCommon_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_ControlLoopCommon_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Control loop proportional gain
// Range of Kp is 0.0f to 50.0f.
_pg_user->Kp = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1310.7f);
// Control loop integral gain
// Range of Ki is 0.0f to 50.0f.
_pg_user->Ki = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1310.7f);
// Control loop derivative
// Range of Kd is 0.0f to 50.0f.
_pg_user->Kd = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1310.7f);
// Control loop feed-forward gain
// Range of Kf is 0.0f to 50.0f.
_pg_user->Kf = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1310.7f);
// Minimum PWM limit for control loop output
// Range of minPwm is 0 to 255.
_pg_user->minPwm = uint8FromBytes(_pg_data, &_pg_byteindex);
// Maximum PWM limit for control loop output
// Range of maxPwm is 0 to 255.
_pg_user->maxPwm = uint8FromBytes(_pg_data, &_pg_byteindex);
// Reserved for future use
// Range of reserved is 0 to 255.
_pg_user->reserved = uint8FromBytes(_pg_data, &_pg_byteindex);
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_ControlLoopCommon_t
// end of ESCDefines.c

View File

@ -1,4 +1,4 @@
// ESCDefines.h was generated by ProtoGen version 3.2.a
// ESCDefines.h was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ESCDEFINES_H
@ -29,6 +29,7 @@ extern "C" {
* \file
*/
#include <stdint.h>
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
@ -48,10 +49,15 @@ typedef struct
bool running; //!< Set if ESC is running
bool anyWarnings; //!< Warning active - refer to the PKT_ESC_WARNINGS_ERRORS packet
bool anyErrors; //!< Error active - refer to the PKT_ESC_WARNINGS_ERRORS packet
bool canArmed; //!< Set if ESC is armed to respond to CAN commands
bool pwmArmed; //!< Set if ESC is armed to respond to PWM Input commands
bool spinning; //!< Set if the motor is spinning (even if it is not being driven)
bool spinningReversed; //!< Set if motor is spinning opposite to configured rotation direction
bool foldback; //!< Set if motor duty cycle is being limited due to ESC protection settings
bool foldback; //!< Set if motor duty cycle is being actively reduced due to ESC protection settings
bool syncing; //!< Set if the ESC is attempting to sync with the motor
bool braking; //!< Set if the ESC is applying motor braking
bool foldforward; //!< Set if the motor duty cycle is being actively increased due to ESC protection settings
bool settingsLocked; //!< Set if the ESC settings are locked and cannot be changed
bool debug; //!< Set if the ESC is in debug mode (factory use only)
}ESC_StatusBits_t;
@ -77,20 +83,24 @@ int decodeESC_StatusBits_t(const uint8_t* data, int* bytecount, ESC_StatusBits_t
*/
typedef struct
{
bool overspeed; //!< Set if the ESC motor speed exceeds the configured warning threshold
bool overcurrent; //!< Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
bool escTemperature; //!< Set if the internal ESC temperature is above the warning threshold
bool motorTemperature; //!< Set if the motor temperature is above the warning threshold
bool undervoltage; //!< Set if the input voltage is below the minimum threshold
bool overvoltage; //!< Set if the input voltage is above the maximum threshold
bool invalidPWMsignal; //!< Set if hardware PWM input is enabled but invalid
bool demagAngle; //!< Set if the motor demag angle exceeds the maximum threshold
bool advanceLimit; //!< Set if the auto-advance exceeds 25 degrees
bool longDemag; //!< Set if the measured demag pulse is exceptionally long
bool missedZeroCrossing; //!< Set if a zero-crossing measurement was missed
bool spinningReversed; //!< Motor is spinning in the wrong direction
bool commSpeedLimit; //!< Motor has reached maximum allowable commutation speed
bool settingsChecksum; //!< Settings checksum does not match programmed value
bool overspeed; //!< Set if the ESC motor speed exceeds the configured warning threshold
bool overcurrent; //!< Set if the ESC DC current (positive, into the motor) exceeds the configured warning threshold
bool escTemperature; //!< Set if the internal ESC temperature is above the warning threshold
bool motorTemperature; //!< Set if the motor temperature is above the warning threshold
bool undervoltage; //!< Set if the input voltage is below the minimum threshold
bool overvoltage; //!< Set if the input voltage is above the maximum threshold
bool invalidPWMsignal; //!< Set if hardware PWM input is enabled but invalid
bool demagAngle; //!< Set if the motor demag angle exceeds the maximum threshold
bool advanceLimit; //!< Set if the auto-advance exceeds 25 degrees
bool longDemag; //!< Set if the measured demag pulse is exceptionally long
bool missedZeroCrossing; //!< Set if a zero-crossing measurement was missed
bool spinningReversed; //!< Motor is spinning in the wrong direction
bool commSpeedLimit; //!< Motor has reached maximum allowable commutation speed
bool settingsChecksum; //!< Settings checksum does not match programmed value
bool highCPUUsage; //!< Set if the ESC's CPU usage is high
bool regenCurrent;
bool hallSensors;
uint16_t reservedWarningBits;
}ESC_WarningBits_t;
//! return the minimum encoded length for the ESC_WarningBits_t structure
@ -105,19 +115,34 @@ void encodeESC_WarningBits_t(uint8_t* data, int* bytecount, const ESC_WarningBit
//! Decode a ESC_WarningBits_t from a byte array
int decodeESC_WarningBits_t(const uint8_t* data, int* bytecount, ESC_WarningBits_t* user);
//! return the minimum encoded length for the ESC_ExtendedWarningBits_t structure
#define getMinLengthOfESC_ExtendedWarningBits_t() 0
//! return the maximum encoded length for the ESC_ExtendedWarningBits_t structure
#define getMaxLengthOfESC_ExtendedWarningBits_t() (2)
//! Encode a ESC_ExtendedWarningBits_t into a byte array
void encodeESC_ExtendedWarningBits_t(uint8_t* data, int* bytecount, const ESC_WarningBits_t* user);
//! Decode a ESC_ExtendedWarningBits_t from a byte array
int decodeESC_ExtendedWarningBits_t(const uint8_t* data, int* bytecount, ESC_WarningBits_t* user);
/*!
* The *error* bits enumerate critical system errors that will cause the ESC to
* stop functioning until the error cases are alleviated
*/
typedef struct
{
bool failedStart; //!< Set if the ESC failed to start the motor
bool commutation; //!< Lost commutation
bool hallSensor; //!< Set if hall sensor error detected
bool overcurrent; //!< Current exceeded hard-limit
bool overtemperature; //!< Temperature exceeded hard-limit
bool overspeed; //!< Motor commutation speed exceeded hard-limit
bool demag; //!< Motor stopped due to high demag angle
bool failedStart; //!< Set if the ESC failed to start the motor
bool commutation; //!< Lost commutation
bool hallSensor; //!< Set if hall sensor error detected
bool overcurrent; //!< Current exceeded hard limit
bool overtemperature; //!< Temperature exceeded hard-limit
bool overspeed; //!< Motor commutation speed exceeded hard-limit
bool demag; //!< Motor stopped due to high demag angle
bool phaseVoltage; //!< Phase voltage error detected
bool regenCurrent; //!< Regen current exceeded hard limit
uint8_t reservedErrorBits;
}ESC_ErrorBits_t;
//! return the minimum encoded length for the ESC_ErrorBits_t structure
@ -132,6 +157,18 @@ void encodeESC_ErrorBits_t(uint8_t* data, int* bytecount, const ESC_ErrorBits_t*
//! Decode a ESC_ErrorBits_t from a byte array
int decodeESC_ErrorBits_t(const uint8_t* data, int* bytecount, ESC_ErrorBits_t* user);
//! return the minimum encoded length for the ESC_ExtendedErrorBits_t structure
#define getMinLengthOfESC_ExtendedErrorBits_t() 0
//! return the maximum encoded length for the ESC_ExtendedErrorBits_t structure
#define getMaxLengthOfESC_ExtendedErrorBits_t() (1)
//! Encode a ESC_ExtendedErrorBits_t into a byte array
void encodeESC_ExtendedErrorBits_t(uint8_t* data, int* bytecount, const ESC_ErrorBits_t* user);
//! Decode a ESC_ExtendedErrorBits_t from a byte array
int decodeESC_ExtendedErrorBits_t(const uint8_t* data, int* bytecount, ESC_ErrorBits_t* user);
/*!
* These bits are used to determine which packets are automatically transmitted
* as telemetry data by the ESC. Only the packets described here can be
@ -142,7 +179,6 @@ typedef struct
bool statusA; //!< If this bit is set, the STATUS_A packet will be transmitted at the configured rate
bool statusB; //!< If this bit is set, the STATUS_B packet will be transmitted at the configured rate
bool statusC; //!< If this bit is set, the STATUS_C packet will be transmitted at the configured rate
bool accelerometer; //!< If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
bool statusD; //!< If this bit is set, the STATUS_D packet will be transmitted at the configured rate
bool reservedTelemA; //!< Reserved for future use
bool piccoloDownlink; //!< If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
@ -169,13 +205,17 @@ typedef struct
{
bool ctrlLoopOutputs; //!< Control loop terms
bool hallSensors; //!< Hall sensor debug information
bool commutation; //!< Commutation debug information
bool commutationA; //!< Commutation A debug information
bool demag; //!< Demag debug information
bool pwmInput; //!< PWM input debug information
bool commutationB; //!< Commutation B debug information
bool commutationC; //!< Commutation C debug information
bool phaseSamples; //!< Direct phase sampling debug information
bool starting; //!< Starting debug information
}ESC_DebugPackets_t;
//! return the minimum encoded length for the ESC_DebugPackets_t structure
#define getMinLengthOfESC_DebugPackets_t() (2)
#define getMinLengthOfESC_DebugPackets_t() (1)
//! return the maximum encoded length for the ESC_DebugPackets_t structure
#define getMaxLengthOfESC_DebugPackets_t() (2)
@ -186,6 +226,29 @@ void encodeESC_DebugPackets_t(uint8_t* data, int* bytecount, const ESC_DebugPack
//! Decode a ESC_DebugPackets_t from a byte array
int decodeESC_DebugPackets_t(const uint8_t* data, int* bytecount, ESC_DebugPackets_t* user);
typedef struct
{
float Kp; //!< Control loop proportional gain
float Ki; //!< Control loop integral gain
float Kd; //!< Control loop derivative
float Kf; //!< Control loop feed-forward gain
uint8_t minPwm; //!< Minimum PWM limit for control loop output
uint8_t maxPwm; //!< Maximum PWM limit for control loop output
uint8_t reserved; //!< Reserved for future use
}ESC_ControlLoopCommon_t;
//! return the minimum encoded length for the ESC_ControlLoopCommon_t structure
#define getMinLengthOfESC_ControlLoopCommon_t() (8)
//! return the maximum encoded length for the ESC_ControlLoopCommon_t structure
#define getMaxLengthOfESC_ControlLoopCommon_t() (11)
//! Encode a ESC_ControlLoopCommon_t into a byte array
void encodeESC_ControlLoopCommon_t(uint8_t* data, int* bytecount, const ESC_ControlLoopCommon_t* user);
//! Decode a ESC_ControlLoopCommon_t from a byte array
int decodeESC_ControlLoopCommon_t(const uint8_t* data, int* bytecount, ESC_ControlLoopCommon_t* user);
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

View File

@ -1,4 +1,4 @@
// ESCPackets.h was generated by ProtoGen version 3.2.a
// ESCPackets.h was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ESCPACKETS_H
@ -29,23 +29,78 @@ extern "C" {
* \file
*/
#include <stdint.h>
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
#include "ESCDefines.h"
typedef struct
{
unsigned reserved : 2;
unsigned polarity : 3;
}ESC_HallSensorPattern_t;
//! return the minimum encoded length for the ESC_HallSensorPattern_t structure
#define getMinLengthOfESC_HallSensorPattern_t() (1)
//! return the maximum encoded length for the ESC_HallSensorPattern_t structure
#define getMaxLengthOfESC_HallSensorPattern_t() (1)
//! Encode a ESC_HallSensorPattern_t into a byte array
void encodeESC_HallSensorPattern_t(uint8_t* data, int* bytecount, const ESC_HallSensorPattern_t* user);
//! Decode a ESC_HallSensorPattern_t from a byte array
int decodeESC_HallSensorPattern_t(const uint8_t* data, int* bytecount, ESC_HallSensorPattern_t* user);
/*!
* RPM control loop settings
*/
typedef struct
{
ESC_ControlLoopCommon_t pid; //!< Core control loop settings
uint16_t rpmRateLimit; //!< RPM setpoint rate limit
float rpmFilter; //!< Corner frequency for RPM measurement LPF
}ESC_RPMControlLoopSettings_t;
//! Create the ESC_RPMControlLoopSettings packet
void encodeESC_RPMControlLoopSettingsPacketStructure(void* pkt, const ESC_RPMControlLoopSettings_t* user);
//! Decode the ESC_RPMControlLoopSettings packet
int decodeESC_RPMControlLoopSettingsPacketStructure(const void* pkt, ESC_RPMControlLoopSettings_t* user);
//! Encode a ESC_RPMControlLoopSettings_t into a byte array
void encodeESC_RPMControlLoopSettings_t(uint8_t* data, int* bytecount, const ESC_RPMControlLoopSettings_t* user);
//! Decode a ESC_RPMControlLoopSettings_t from a byte array
int decodeESC_RPMControlLoopSettings_t(const uint8_t* data, int* bytecount, ESC_RPMControlLoopSettings_t* user);
//! return the packet ID for the ESC_RPMControlLoopSettings packet
#define getESC_RPMControlLoopSettingsPacketID() (PKT_ESC_RPM_LOOP_SETTINGS)
//! return the minimum encoded length for the ESC_RPMControlLoopSettings packet
#define getESC_RPMControlLoopSettingsMinDataLength() (8)
//! return the maximum encoded length for the ESC_RPMControlLoopSettings packet
#define getESC_RPMControlLoopSettingsMaxDataLength() (15)
/*!
* General ESC configuration parameters
*/
typedef struct
{
bool swInhibit; //!< 1 = ESC is inhibited (disabled) on startup
bool piccoloCommands; //!< 1 = ESC will respond to PICCOLO autopilot commands
bool broadcastCommands; //!< 1 = ESC will accept broadcast command messages
uint8_t commandInputPriority; //!< Command input source priority, refer to enumeration ESCCommandPriorities
uint8_t motorTempSensor; //!< External motor temperature sensor configuration
uint8_t keepalive; //!< ESC keepalive timeout - If this is non-zero, the ESC will automatically revert to *STANDBY* mode if it does not receive a valid command for the alloted period
uint8_t motorBeepMode;
uint8_t motorBeepVolume; //!< Motor beep volume
bool swInhibit; //!< 1 = ESC is inhibited (disabled) on startup
bool piccoloCommands; //!< 1 = ESC will respond to PICCOLO autopilot commands
bool broadcastCommands; //!< 1 = ESC will accept broadcast command messages
bool enablePwmInput; //!< 1 = Digital PWM input is enabled
uint8_t motorTempSensor; //!< External motor temperature sensor configuration
uint8_t keepalive; //!< ESC keepalive timeout - If this is non-zero, the ESC will automatically revert to *STANDBY* mode if it does not receive a valid command for the alloted period
uint8_t disableLED; //!< 1 = Disable LED
uint8_t canBitRate; //!< CAN bit (baud) rate
uint8_t canProtocol; //!< Protocol to communicate over CAN
bool motorBraking; //!< Enable motor brake strength (applied when motor is off)
uint8_t swInhibitDelay; //!< Delay between hardware inhibit and software inhibit events
uint8_t motorBeepMode; //!< Sets the motor beep mode for the ESC
uint8_t motorBeepVolume; //!< Motor beep volume
}ESC_Config_t;
//! Create the ESC_Config packet
@ -55,10 +110,10 @@ void encodeESC_ConfigPacketStructure(void* pkt, const ESC_Config_t* user);
int decodeESC_ConfigPacketStructure(const void* pkt, ESC_Config_t* user);
//! Create the ESC_Config packet from parameters
void encodeESC_ConfigPacket(void* pkt, bool swInhibit, bool piccoloCommands, bool broadcastCommands, uint8_t commandInputPriority, uint8_t motorTempSensor, uint8_t keepalive, uint8_t motorBeepMode, uint8_t motorBeepVolume);
void encodeESC_ConfigPacket(void* pkt, bool swInhibit, bool piccoloCommands, bool broadcastCommands, bool enablePwmInput, uint8_t motorTempSensor, uint8_t keepalive, uint8_t disableLED, uint8_t canBitRate, uint8_t canProtocol, bool motorBraking, uint8_t swInhibitDelay, uint8_t motorBeepMode, uint8_t motorBeepVolume);
//! Decode the ESC_Config packet to parameters
int decodeESC_ConfigPacket(const void* pkt, bool* swInhibit, bool* piccoloCommands, bool* broadcastCommands, uint8_t* commandInputPriority, uint8_t* motorTempSensor, uint8_t* keepalive, uint8_t* motorBeepMode, uint8_t* motorBeepVolume);
int decodeESC_ConfigPacket(const void* pkt, bool* swInhibit, bool* piccoloCommands, bool* broadcastCommands, bool* enablePwmInput, uint8_t* motorTempSensor, uint8_t* keepalive, uint8_t* disableLED, uint8_t* canBitRate, uint8_t* canProtocol, bool* motorBraking, uint8_t* swInhibitDelay, uint8_t* motorBeepMode, uint8_t* motorBeepVolume);
//! Encode a ESC_Config_t into a byte array
void encodeESC_Config_t(uint8_t* data, int* bytecount, const ESC_Config_t* user);
@ -113,18 +168,18 @@ int decodeESC_TelemetryConfig_t(const uint8_t* data, int* bytecount, ESC_Telemet
#define getESC_TelemetryConfigMaxDataLength() (3)
/*!
* Send this packet to command ESCs which have CAN ID values in the range {1,4}
* (inclusive). This packet must be sent as a broadcast packet (address = 0xFF)
* such that all ESCs can receive it. Similiar commands are available for
* commanding ESCs with ID values up to 64, using different ESC_SETPOINT_x
* packet ID values.
* This packet can be used to simultaneously command multiple ESCs which have
* sequential CAN ID values. This packet must be sent as a broadcast packet
* (address = 0xFF) such that all ESCs can receive it. These commands can be
* sent to groups of ESCs with ID values up to 64, using different
* ESC_SETPOINT_x packet ID values.
*/
typedef struct
{
uint16_t pwmValueA; //!< The PWM (pulse width) command for ESC with CAN ID 1
uint16_t pwmValueB; //!< The PWM (pulse width) command for ESC with CAN ID 2
uint16_t pwmValueC; //!< The PWM (pulse width) command for ESC with CAN ID 3
uint16_t pwmValueD; //!< The PWM (pulse width) command for ESC with CAN ID 4
uint16_t pwmValueA; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 1]
uint16_t pwmValueB; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 2]
uint16_t pwmValueC; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 3]
uint16_t pwmValueD; //!< The PWM (pulse width) command for ESC with CAN ID [PKT_ID + 4]
}ESC_CommandMultipleESCs_t;
//! Create the ESC_CommandMultipleESCs packet from parameters
@ -169,16 +224,6 @@ int decodeESC_EnablePacket(const void* pkt);
//! return the maximum encoded length for the ESC_Enable packet
#define getESC_EnableMaxDataLength() (2)
/*!
* 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.
*/
typedef struct
{
uint16_t pwmCommand; //!< PWM command
}ESC_PWMCommand_t;
//! Create the ESC_PWMCommand packet from parameters
void encodeESC_PWMCommandPacket(void* pkt, uint16_t pwmCommand);
@ -194,15 +239,6 @@ int decodeESC_PWMCommandPacket(const void* pkt, uint16_t* pwmCommand);
//! return the maximum encoded length for the ESC_PWMCommand packet
#define getESC_PWMCommandMaxDataLength() (2)
/*!
* 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
*/
typedef struct
{
uint16_t rpmCommand; //!< RPM Command
}ESC_RPMCommand_t;
//! Create the ESC_RPMCommand packet from parameters
void encodeESC_RPMCommandPacket(void* pkt, uint16_t rpmCommand);
@ -218,6 +254,21 @@ int decodeESC_RPMCommandPacket(const void* pkt, uint16_t* rpmCommand);
//! return the maximum encoded length for the ESC_RPMCommand packet
#define getESC_RPMCommandMaxDataLength() (2)
//! Create the ESC_VoltageCommand packet from parameters
void encodeESC_VoltageCommandPacket(void* pkt, uint16_t voltageCommand);
//! Decode the ESC_VoltageCommand packet to parameters
int decodeESC_VoltageCommandPacket(const void* pkt, uint16_t* voltageCommand);
//! return the packet ID for the ESC_VoltageCommand packet
#define getESC_VoltageCommandPacketID() (PKT_ESC_VOLT_CMD)
//! return the minimum encoded length for the ESC_VoltageCommand packet
#define getESC_VoltageCommandMinDataLength() (2)
//! return the maximum encoded length for the ESC_VoltageCommand packet
#define getESC_VoltageCommandMaxDataLength() (2)
/*!
* The ESC_STATUS_A packet contains high-priority ESC status information. This
* packet is transmitted by the ESC at regular (user-configurable) intervals.
@ -232,6 +283,12 @@ typedef struct
uint16_t rpm; //!< Motor speed
}ESC_StatusA_t;
//! Create the ESC_StatusA packet
void encodeESC_StatusAPacketStructure(void* pkt, const ESC_StatusA_t* user);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacketStructure(const void* pkt, ESC_StatusA_t* user);
//! Create the ESC_StatusA packet from parameters
void encodeESC_StatusAPacket(void* pkt, uint8_t mode, const ESC_StatusBits_t* status, uint16_t command, uint16_t rpm);
@ -262,6 +319,12 @@ typedef struct
uint8_t motorTemperature; //!< ESC Motor Temperature
}ESC_StatusB_t;
//! Create the ESC_StatusB packet
void encodeESC_StatusBPacketStructure(void* pkt, const ESC_StatusB_t* user);
//! Decode the ESC_StatusB packet
int decodeESC_StatusBPacketStructure(const void* pkt, ESC_StatusB_t* user);
//! Create the ESC_StatusB packet from parameters
void encodeESC_StatusBPacket(void* pkt, uint16_t voltage, int16_t current, uint16_t dutyCycle, int8_t escTemperature, uint8_t motorTemperature);
@ -278,8 +341,10 @@ int decodeESC_StatusBPacket(const void* pkt, uint16_t* voltage, int16_t* current
#define getESC_StatusBMaxDataLength() (8)
/*!
* ESC Status C telemetry packet transmitted by the ESC at regular intervals
* (reserved for future use)
* The ESC_STATUS_C packet contains ESC operational information. This packet is
* transmitted by the ESC at regular intervals (user-configurable). It can also
* be requested (polled) from the ESC by sending a zero-length packet of the
* same type.
*/
typedef struct
{
@ -288,6 +353,12 @@ typedef struct
uint16_t timingAdvance; //!< Current timing advance (0.1 degree per bit)
}ESC_StatusC_t;
//! Create the ESC_StatusC packet
void encodeESC_StatusCPacketStructure(void* pkt, const ESC_StatusC_t* user);
//! Decode the ESC_StatusC packet
int decodeESC_StatusCPacketStructure(const void* pkt, ESC_StatusC_t* user);
//! Create the ESC_StatusC packet from parameters
void encodeESC_StatusCPacket(void* pkt, float fetTemperature, uint16_t pwmFrequency, uint16_t timingAdvance);
@ -304,55 +375,56 @@ int decodeESC_StatusCPacket(const void* pkt, float* fetTemperature, uint16_t* pw
#define getESC_StatusCMaxDataLength() (7)
/*!
* 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
* The ESC_STATUS_D packet contains ESC operational information. This packet is
* transmitted by the ESC at regular intervals (user-configurable). It can also
* be requested (polled) from the ESC by sending a zero-length packet of the
* same type.
*/
typedef struct
{
int16_t xAcc; //!< X axis acceleration value
int16_t yAcc; //!< Y axis acceleration value
int16_t zAcc; //!< Z axis acceleration value
uint8_t fullscale; //!< Accelerometer full-scale range
uint8_t resolution; //!< Accelerometer measurement resolution, in 'bits'.
}ESC_Accelerometer_t;
uint8_t demagAngle; //!< Measured demag angle of motor
}ESC_StatusD_t;
//! Create the ESC_Accelerometer packet from parameters
void encodeESC_AccelerometerPacket(void* pkt, int16_t xAcc, int16_t yAcc, int16_t zAcc, uint8_t fullscale, uint8_t resolution);
//! Create the ESC_StatusD packet
void encodeESC_StatusDPacketStructure(void* pkt, const ESC_StatusD_t* user);
//! Decode the ESC_Accelerometer packet to parameters
int decodeESC_AccelerometerPacket(const void* pkt, int16_t* xAcc, int16_t* yAcc, int16_t* zAcc, uint8_t* fullscale, uint8_t* resolution);
//! Decode the ESC_StatusD packet
int decodeESC_StatusDPacketStructure(const void* pkt, ESC_StatusD_t* user);
//! return the packet ID for the ESC_Accelerometer packet
#define getESC_AccelerometerPacketID() (PKT_ESC_ACCELEROMETER)
//! Create the ESC_StatusD packet from parameters
void encodeESC_StatusDPacket(void* pkt, uint8_t demagAngle);
//! return the minimum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMinDataLength() (8)
//! Decode the ESC_StatusD packet to parameters
int decodeESC_StatusDPacket(const void* pkt, uint8_t* demagAngle);
//! return the maximum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMaxDataLength() (8)
//! return the packet ID for the ESC_StatusD packet
#define getESC_StatusDPacketID() (PKT_ESC_STATUS_D)
//! return the minimum encoded length for the ESC_StatusD packet
#define getESC_StatusDMinDataLength() (8)
//! return the maximum encoded length for the ESC_StatusD packet
#define getESC_StatusDMaxDataLength() (8)
/*!
* Warning and error status information
* Warning and error status information. If any warning or error flags are set,
* this packet is transmitted by the ESC at 10Hz. If there are no warning or
* error flags set, the packet is transmitted by the ESC at 1Hz.
*/
typedef struct
{
ESC_WarningBits_t warnings;
ESC_ErrorBits_t errors;
ESC_WarningBits_t warnings; //!< ESC warning bitfield
ESC_ErrorBits_t errors; //!< ESC error bitfield
uint8_t extended; //!< Set to indicate that this packet contains extended warning and error information
ESC_WarningBits_t warningsExtended; //!< Extension of ESC warning bitfield
ESC_ErrorBits_t errorsExtended; //!< Extension of ESC error bifield
}ESC_WarningErrorStatus_t;
//! Create the ESC_WarningErrorStatus packet
void encodeESC_WarningErrorStatusPacketStructure(void* pkt, const ESC_WarningErrorStatus_t* user);
//! Decode the ESC_WarningErrorStatus packet
int decodeESC_WarningErrorStatusPacketStructure(const void* pkt, ESC_WarningErrorStatus_t* user);
//! Create the ESC_WarningErrorStatus packet from parameters
void encodeESC_WarningErrorStatusPacket(void* pkt, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors);
void encodeESC_WarningErrorStatusPacket(void* pkt, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors, uint8_t extended, const ESC_WarningBits_t* warningsExtended, const ESC_ErrorBits_t* errorsExtended);
//! Decode the ESC_WarningErrorStatus packet to parameters
int decodeESC_WarningErrorStatusPacket(const void* pkt, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors);
int decodeESC_WarningErrorStatusPacket(const void* pkt, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors, uint8_t* extended, ESC_WarningBits_t* warningsExtended, ESC_ErrorBits_t* errorsExtended);
//! return the packet ID for the ESC_WarningErrorStatus packet
#define getESC_WarningErrorStatusPacketID() (PKT_ESC_WARNINGS_ERRORS)
@ -361,10 +433,67 @@ int decodeESC_WarningErrorStatusPacket(const void* pkt, ESC_WarningBits_t* warni
#define getESC_WarningErrorStatusMinDataLength() (4)
//! return the maximum encoded length for the ESC_WarningErrorStatus packet
#define getESC_WarningErrorStatusMaxDataLength() (4)
#define getESC_WarningErrorStatusMaxDataLength() (8)
/*!
* Motor status flags
* This packet contains the current output values for the RPM controller.
*/
typedef struct
{
float pTerm;
float iTerm;
float fTerm;
int16_t output; //!< Output duty cycle
}ESC_ControlLoopOutputs_t;
//! Create the ESC_ControlLoopOutputs packet
void encodeESC_ControlLoopOutputsPacketStructure(void* pkt, const ESC_ControlLoopOutputs_t* user);
//! Decode the ESC_ControlLoopOutputs packet
int decodeESC_ControlLoopOutputsPacketStructure(const void* pkt, ESC_ControlLoopOutputs_t* user);
//! Create the ESC_ControlLoopOutputs packet from parameters
void encodeESC_ControlLoopOutputsPacket(void* pkt, float pTerm, float iTerm, float fTerm, int16_t output);
//! Decode the ESC_ControlLoopOutputs packet to parameters
int decodeESC_ControlLoopOutputsPacket(const void* pkt, float* pTerm, float* iTerm, float* fTerm, int16_t* output);
//! return the packet ID for the ESC_ControlLoopOutputs packet
#define getESC_ControlLoopOutputsPacketID() (PKT_ESC_CONTROL_LOOP_DATA)
//! return the minimum encoded length for the ESC_ControlLoopOutputs packet
#define getESC_ControlLoopOutputsMinDataLength() (8)
//! return the maximum encoded length for the ESC_ControlLoopOutputs packet
#define getESC_ControlLoopOutputsMaxDataLength() (8)
/*!
* This packet contains information on the hall sensor
*/
typedef struct
{
ESC_HallSensorPattern_t detectedPattern;
}ESC_HallSensorInfo_t;
//! Create the ESC_HallSensorInfo packet from parameters
void encodeESC_HallSensorInfoPacket(void* pkt, const ESC_HallSensorPattern_t* detectedPattern);
//! Decode the ESC_HallSensorInfo packet to parameters
int decodeESC_HallSensorInfoPacket(const void* pkt, ESC_HallSensorPattern_t* detectedPattern);
//! return the packet ID for the ESC_HallSensorInfo packet
#define getESC_HallSensorInfoPacketID() (PKT_ESC_HALL_SENSOR_INFO)
//! return the minimum encoded length for the ESC_HallSensorInfo packet
#define getESC_HallSensorInfoMinDataLength() (1)
//! return the maximum encoded length for the ESC_HallSensorInfo packet
#define getESC_HallSensorInfoMaxDataLength() (1)
/*!
* Motor status flags. If any warning or error flags are set, this packet is
* transmitted by the ESC at 10Hz. If there are no warning or error flags set,
* the packet is transmitted by the ESC at 1Hz.
*/
typedef struct
{
@ -395,6 +524,166 @@ int decodeESC_MotorStatusFlagsPacket(const void* pkt, uint16_t* standbyCause, ui
//! return the maximum encoded length for the ESC_MotorStatusFlags packet
#define getESC_MotorStatusFlagsMaxDataLength() (8)
/*!
* Voltage control loop settings
*/
typedef struct
{
ESC_ControlLoopCommon_t pid; //!< Core control loop settings
}ESC_VoltageControlLoopSettings_t;
//! Create the ESC_VoltageControlLoopSettings packet
void encodeESC_VoltageControlLoopSettingsPacketStructure(void* pkt, const ESC_VoltageControlLoopSettings_t* user);
//! Decode the ESC_VoltageControlLoopSettings packet
int decodeESC_VoltageControlLoopSettingsPacketStructure(const void* pkt, ESC_VoltageControlLoopSettings_t* user);
//! Create the ESC_VoltageControlLoopSettings packet from parameters
void encodeESC_VoltageControlLoopSettingsPacket(void* pkt, const ESC_ControlLoopCommon_t* pid);
//! Decode the ESC_VoltageControlLoopSettings packet to parameters
int decodeESC_VoltageControlLoopSettingsPacket(const void* pkt, ESC_ControlLoopCommon_t* pid);
//! return the packet ID for the ESC_VoltageControlLoopSettings packet
#define getESC_VoltageControlLoopSettingsPacketID() (PKT_ESC_VOLT_LOOP_SETTINGS)
//! return the minimum encoded length for the ESC_VoltageControlLoopSettings packet
#define getESC_VoltageControlLoopSettingsMinDataLength() (8)
//! return the maximum encoded length for the ESC_VoltageControlLoopSettings packet
#define getESC_VoltageControlLoopSettingsMaxDataLength() (11)
/*!
* ESC self-protection settings
*/
typedef struct
{
float overcurrentBus; //!< Maximum allowable DC bus current
float overcurrentPhase; //!< Maximum allowable motor phase current
float overcurrentRegen; //!< Maximum allowable regen current
uint8_t overtemperatureInternal; //!< Maximum allowable internal temperature
uint8_t overtemperatureMotor; //!< Maximum allowable motor temperature
uint16_t overspeed; //!< Maximum motor speed
uint8_t undervoltage; //!< ESC undervoltage warning threshold
uint8_t overvoltage; //!< ESC overvoltage warning threshold
uint8_t demagAngle; //!< Maximum allowable demag angle
uint8_t timingAdvance; //!< Maximum allowable timing advance
}ESC_ProtectionValues_t;
//! Create the ESC_ProtectionValues packet
void encodeESC_ProtectionValuesPacketStructure(void* pkt, const ESC_ProtectionValues_t* user);
//! Decode the ESC_ProtectionValues packet
int decodeESC_ProtectionValuesPacketStructure(const void* pkt, ESC_ProtectionValues_t* user);
//! Create the ESC_ProtectionValues packet from parameters
void encodeESC_ProtectionValuesPacket(void* pkt, float overcurrentBus, float overcurrentPhase, float overcurrentRegen, uint8_t overtemperatureInternal, uint8_t overtemperatureMotor, uint16_t overspeed, uint8_t undervoltage, uint8_t overvoltage, uint8_t demagAngle, uint8_t timingAdvance);
//! Decode the ESC_ProtectionValues packet to parameters
int decodeESC_ProtectionValuesPacket(const void* pkt, float* overcurrentBus, float* overcurrentPhase, float* overcurrentRegen, uint8_t* overtemperatureInternal, uint8_t* overtemperatureMotor, uint16_t* overspeed, uint8_t* undervoltage, uint8_t* overvoltage, uint8_t* demagAngle, uint8_t* timingAdvance);
//! return the packet ID for the ESC_ProtectionValues packet
#define getESC_ProtectionValuesPacketID() (PKT_ESC_PROTECTION_LEVELS)
//! return the minimum encoded length for the ESC_ProtectionValues packet
#define getESC_ProtectionValuesMinDataLength() (10)
//! return the maximum encoded length for the ESC_ProtectionValues packet
#define getESC_ProtectionValuesMaxDataLength() (11)
/*!
* ESC protection actions
*/
typedef struct
{
uint8_t overcurrentBus; //!< Action when bus current exceeds limit
uint8_t overcurrentPhase; //!< Action when phase current exceeds limit
uint8_t overcurrentRegen; //!< Action when regen current exceeds limit
uint8_t overtemperatureInternal; //!< Action when ESC temperature exceeds limit
uint8_t overtemperatureMotor; //!< Action when motor temperature exceeds limit
uint8_t overspeed; //!< Action when motor speed exceeds limit
uint8_t undervoltage; //!< Action when DC voltage falls below configured lower limit
uint8_t overvoltage; //!< Action when DC voltage exceeds configured upper limit
uint8_t demagAngle; //!< Action when motor demag angle exceeds limit
uint8_t commutationLoss; //!< Action on motor commutation estimator failure
}ESC_ProtectionActions_t;
//! Create the ESC_ProtectionActions packet
void encodeESC_ProtectionActionsPacketStructure(void* pkt, const ESC_ProtectionActions_t* user);
//! Decode the ESC_ProtectionActions packet
int decodeESC_ProtectionActionsPacketStructure(const void* pkt, ESC_ProtectionActions_t* user);
//! Create the ESC_ProtectionActions packet from parameters
void encodeESC_ProtectionActionsPacket(void* pkt, uint8_t overcurrentBus, uint8_t overcurrentPhase, uint8_t overcurrentRegen, uint8_t overtemperatureInternal, uint8_t overtemperatureMotor, uint8_t overspeed, uint8_t undervoltage, uint8_t overvoltage, uint8_t demagAngle, uint8_t commutationLoss);
//! Decode the ESC_ProtectionActions packet to parameters
int decodeESC_ProtectionActionsPacket(const void* pkt, uint8_t* overcurrentBus, uint8_t* overcurrentPhase, uint8_t* overcurrentRegen, uint8_t* overtemperatureInternal, uint8_t* overtemperatureMotor, uint8_t* overspeed, uint8_t* undervoltage, uint8_t* overvoltage, uint8_t* demagAngle, uint8_t* commutationLoss);
//! return the packet ID for the ESC_ProtectionActions packet
#define getESC_ProtectionActionsPacketID() (PKT_ESC_PROTECTION_ACTIONS)
//! return the minimum encoded length for the ESC_ProtectionActions packet
#define getESC_ProtectionActionsMinDataLength() (3)
//! return the maximum encoded length for the ESC_ProtectionActions packet
#define getESC_ProtectionActionsMaxDataLength() (4)
/*!
* Motor and system parameters
*/
typedef struct
{
uint8_t reserved; //!< Reserved for future packet expansion. Field is encoded constant.
uint16_t motorKv; //!< Motor RPM constant
uint8_t polePairs; //!< Motor pole pairs count
uint16_t maxSpeed; //!< Maximum motor speed
}ESC_MotorParameters_t;
//! Create the ESC_MotorParameters packet
void encodeESC_MotorParametersPacketStructure(void* pkt, const ESC_MotorParameters_t* user);
//! Decode the ESC_MotorParameters packet
int decodeESC_MotorParametersPacketStructure(const void* pkt, ESC_MotorParameters_t* user);
//! return the packet ID for the ESC_MotorParameters packet
#define getESC_MotorParametersPacketID() (PKT_ESC_MOTOR_PARAMETERS)
//! return the minimum encoded length for the ESC_MotorParameters packet
#define getESC_MotorParametersMinDataLength() (4)
//! return the maximum encoded length for the ESC_MotorParameters packet
#define getESC_MotorParametersMaxDataLength() (6)
/*!
* Hall sensor configuration options
*/
typedef struct
{
bool bypassStartingChecks; //!< Bypass extra checks for starting in hall sensor mode
uint8_t mode; //!< Hall sensor operational mode
uint8_t polarity; //!< Hall sensor U/V/W polarity
uint16_t timeout; //!< Time (in milliseconds) for no hall sensor transitions to trigger an error (0 = forever)
uint16_t maxSpeed; //!< Maximum electrical RPM when running under hall sensor control
uint16_t transitionSpeed; //!< RPM threshold for transferring to sensorless motor control
uint8_t transitionHysteresis; //!< RPM hysteresis for switching between sensored and sensorless control
}ESC_MotorHallSensorConfig_t;
//! Create the ESC_MotorHallSensorConfig packet
void encodeESC_MotorHallSensorConfigPacketStructure(void* pkt, const ESC_MotorHallSensorConfig_t* user);
//! Decode the ESC_MotorHallSensorConfig packet
int decodeESC_MotorHallSensorConfigPacketStructure(const void* pkt, ESC_MotorHallSensorConfig_t* user);
//! return the packet ID for the ESC_MotorHallSensorConfig packet
#define getESC_MotorHallSensorConfigPacketID() (PKT_ESC_MOTOR_HALL_CONFIG)
//! return the minimum encoded length for the ESC_MotorHallSensorConfig packet
#define getESC_MotorHallSensorConfigMinDataLength() (9)
//! return the maximum encoded length for the ESC_MotorHallSensorConfig packet
#define getESC_MotorHallSensorConfigMaxDataLength() (9)
/*!
* This packet contains the serial number for the ESC. Additionally there are
* two extra values (each 16-bit) which can be programmed by the user for any
@ -439,6 +728,12 @@ typedef struct
uint8_t ESCTitle[8]; //!< Description of this ESC
}ESC_Title_t;
//! Create the ESC_Title packet
void encodeESC_TitlePacketStructure(void* pkt, const ESC_Title_t* user);
//! Decode the ESC_Title packet
int decodeESC_TitlePacketStructure(const void* pkt, ESC_Title_t* user);
//! Create the ESC_Title packet from parameters
void encodeESC_TitlePacket(void* pkt, const uint8_t ESCTitle[8]);
@ -529,6 +824,12 @@ typedef struct
char apiVersion[5]; //!< The API version of the ESC. Field is encoded constant.
}ESC_TelemetrySettings_t;
//! Create the ESC_TelemetrySettings packet
void encodeESC_TelemetrySettingsPacketStructure(void* pkt, const ESC_TelemetrySettings_t* user);
//! Decode the ESC_TelemetrySettings packet
int decodeESC_TelemetrySettingsPacketStructure(const void* pkt, ESC_TelemetrySettings_t* user);
//! Create the ESC_TelemetrySettings packet from parameters
void encodeESC_TelemetrySettingsPacket(void* pkt, const ESC_TelemetryConfig_t* settings);
@ -578,7 +879,38 @@ int decodeESC_EEPROMSettingsPacket(const void* pkt, bool* settingsLocked, uint8_
#define getESC_EEPROMSettingsMaxDataLength() (7)
/*!
* ESC telltales
* Motor temperature sensor settings
*/
typedef struct
{
int16_t NTC_T[3]; //!< Reference temperature values
float NTC_R[3]; //!< Reference resistance values
uint16_t Beta; //!< Beta constant
}ESC_TempSensorConfig_t;
//! Create the ESC_TempSensorConfig packet
void encodeESC_TempSensorConfigPacketStructure(void* pkt, const ESC_TempSensorConfig_t* user);
//! Decode the ESC_TempSensorConfig packet
int decodeESC_TempSensorConfigPacketStructure(const void* pkt, ESC_TempSensorConfig_t* user);
//! Create the ESC_TempSensorConfig packet from parameters
void encodeESC_TempSensorConfigPacket(void* pkt, const int16_t NTC_T[3], const float NTC_R[3], uint16_t Beta);
//! Decode the ESC_TempSensorConfig packet to parameters
int decodeESC_TempSensorConfigPacket(const void* pkt, int16_t NTC_T[3], float NTC_R[3], uint16_t* Beta);
//! return the packet ID for the ESC_TempSensorConfig packet
#define getESC_TempSensorConfigPacketID() (PKT_ESC_MOTOR_TEMP_SENSOR)
//! return the minimum encoded length for the ESC_TempSensorConfig packet
#define getESC_TempSensorConfigMinDataLength() (20)
//! return the maximum encoded length for the ESC_TempSensorConfig packet
#define getESC_TempSensorConfigMaxDataLength() (20)
/*!
* ESC telltale values
*/
typedef struct
{
@ -624,6 +956,12 @@ typedef struct
char hash[8]; //!< git commit hash
}ESC_GitHash_t;
//! Create the ESC_GitHash packet
void encodeESC_GitHashPacketStructure(void* pkt, const ESC_GitHash_t* user);
//! Decode the ESC_GitHash packet
int decodeESC_GitHashPacketStructure(const void* pkt, ESC_GitHash_t* user);
//! Create the ESC_GitHash packet from parameters
void encodeESC_GitHashPacket(void* pkt, const char hash[8]);
@ -644,6 +982,7 @@ int decodeESC_GitHashPacket(const void* pkt, char hash[8]);
*/
typedef struct
{
bool glitchFilter; //!< Enable median glitch filter for PWM input
uint8_t protocol; //!< Protocol version (reserved for future use). Field is encoded constant.
int8_t pwmOffset; //!< PWM offset compensation value
uint16_t inputMin; //!< PWM value corresponding with 0% throttle
@ -658,10 +997,10 @@ void encodeESC_PWMInputCalibrationPacketStructure(void* pkt, const ESC_PWMInputC
int decodeESC_PWMInputCalibrationPacketStructure(const void* pkt, ESC_PWMInputCalibration_t* user);
//! Create the ESC_PWMInputCalibration packet from parameters
void encodeESC_PWMInputCalibrationPacket(void* pkt, int8_t pwmOffset, uint16_t inputMin, uint16_t inputMax, uint16_t armThreshold);
void encodeESC_PWMInputCalibrationPacket(void* pkt, bool glitchFilter, int8_t pwmOffset, uint16_t inputMin, uint16_t inputMax, uint16_t armThreshold);
//! Decode the ESC_PWMInputCalibration packet to parameters
int decodeESC_PWMInputCalibrationPacket(const void* pkt, uint8_t* protocol, int8_t* pwmOffset, uint16_t* inputMin, uint16_t* inputMax, uint16_t* armThreshold);
int decodeESC_PWMInputCalibrationPacket(const void* pkt, bool* glitchFilter, uint8_t* protocol, int8_t* pwmOffset, uint16_t* inputMin, uint16_t* inputMax, uint16_t* armThreshold);
//! return the packet ID for the ESC_PWMInputCalibration packet
#define getESC_PWMInputCalibrationPacketID() (PKT_ESC_PWM_INPUT_CALIBRATION)

View File

@ -1,4 +1,4 @@
// ESCVelocityProtocol.c was generated by ProtoGen version 3.2.a
// ESCVelocityProtocol.c was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#include "ESCVelocityProtocol.h"
@ -32,13 +32,15 @@ const char* ESCOperatingModes_EnumLabel(int value)
default:
return "";
case ESC_MODE_STANDBY:
return translateESCVelocity("ESC_MODE_STANDBY");
return "ESC_MODE_STANDBY";
case ESC_MODE_PWM:
return translateESCVelocity("ESC_MODE_PWM");
return "ESC_MODE_PWM";
case ESC_MODE_RPM:
return translateESCVelocity("ESC_MODE_RPM");
return "ESC_MODE_RPM";
case ESC_MODE_VOLT:
return "ESC_MODE_VOLT";
case ESC_VALID_MODES:
return translateESCVelocity("ESC_VALID_MODES");
return "ESC_VALID_MODES";
}
}
@ -56,11 +58,11 @@ const char* ESCCommandSources_EnumLabel(int value)
default:
return "";
case ESC_COMMAND_SOURCE_NONE:
return translateESCVelocity("ESC_COMMAND_SOURCE_NONE");
return "ESC_COMMAND_SOURCE_NONE";
case ESC_COMMAND_SOURCE_CAN:
return translateESCVelocity("ESC_COMMAND_SOURCE_CAN");
return "ESC_COMMAND_SOURCE_CAN";
case ESC_COMMAND_SOURCE_PWM:
return translateESCVelocity("ESC_COMMAND_SOURCE_PWM");
return "ESC_COMMAND_SOURCE_PWM";
}
}
@ -78,35 +80,15 @@ const char* ESCMotorTemperatureSensor_EnumLabel(int value)
default:
return "";
case ESC_MOTOR_TEMP_SENSOR_OFF:
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_OFF");
return "ESC_MOTOR_TEMP_SENSOR_OFF";
case ESC_MOTOR_TEMP_SENSOR_KTY84:
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_KTY84");
return "ESC_MOTOR_TEMP_SENSOR_KTY84";
case ESC_MOTOR_TEMP_SENSOR_KTY83:
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_KTY83");
case ESC_MOTOR_TEMP_SENSOR_CUSTOM:
return translateESCVelocity("ESC_MOTOR_TEMP_SENSOR_CUSTOM");
}
}
/*!
* \brief Lookup label for 'ESCCommandPriorities' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCCommandPriorities_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_COMMAND_PRIORITY_CAN_ONLY:
return translateESCVelocity("ESC_COMMAND_PRIORITY_CAN_ONLY");
case ESC_COMMAND_PRIORITY_CAN_PRIORITY:
return translateESCVelocity("ESC_COMMAND_PRIORITY_CAN_PRIORITY");
case ESC_COMMAND_PRIORITY_PWM_PRIORITY:
return translateESCVelocity("ESC_COMMAND_PRIORITY_PWM_PRIORITY");
return "ESC_MOTOR_TEMP_SENSOR_KTY83";
case ESC_MOTOR_TEMP_SENSOR_NTC_SH:
return "ESC_MOTOR_TEMP_SENSOR_NTC_SH";
case ESC_MOTOR_TEMP_SENSOR_NTC_BETA:
return "ESC_MOTOR_TEMP_SENSOR_NTC_BETA";
}
}
@ -124,11 +106,11 @@ const char* ESCMotorDirection_EnumLabel(int value)
default:
return "";
case ESC_MOTOR_DIR_ABC:
return translateESCVelocity("ESC_MOTOR_DIR_ABC");
return "ESC_MOTOR_DIR_ABC";
case ESC_MOTOR_DIR_ACB:
return translateESCVelocity("ESC_MOTOR_DIR_ACB");
return "ESC_MOTOR_DIR_ACB";
case ESC_MOTOR_DIR_OTHER:
return translateESCVelocity("ESC_MOTOR_DIR_OTHER");
return "ESC_MOTOR_DIR_OTHER";
}
}
@ -146,11 +128,11 @@ const char* ESCHallSensorMode_EnumLabel(int value)
default:
return "";
case ESC_HALL_MODE_SENSORLESS:
return translateESCVelocity("ESC_HALL_MODE_SENSORLESS");
return "ESC_HALL_MODE_SENSORLESS";
case ESC_HALL_MODE_SENSORED:
return translateESCVelocity("ESC_HALL_MODE_SENSORED");
case ESC_HALL_MODE_SENSORED_STARTING:
return translateESCVelocity("ESC_HALL_MODE_SENSORED_STARTING");
return "ESC_HALL_MODE_SENSORED";
case ESC_HALL_MODE_HYBRID:
return "ESC_HALL_MODE_HYBRID";
}
}
@ -168,13 +150,13 @@ const char* ESCAFWModes_EnumLabel(int value)
default:
return "";
case ESC_AFW_MODE_OFF:
return translateESCVelocity("ESC_AFW_MODE_OFF");
return "ESC_AFW_MODE_OFF";
case ESC_AFW_MODE_ON:
return translateESCVelocity("ESC_AFW_MODE_ON");
return "ESC_AFW_MODE_ON";
case ESC_AFW_MODE_DYNAMIC:
return translateESCVelocity("ESC_AFW_MODE_DYNAMIC");
return "ESC_AFW_MODE_DYNAMIC";
case ESC_AFW_MODE_OTHER:
return translateESCVelocity("ESC_AFW_MODE_OTHER");
return "ESC_AFW_MODE_OTHER";
}
}
@ -192,11 +174,11 @@ const char* ESCPWMFreqModes_EnumLabel(int value)
default:
return "";
case ESC_PWM_FREQ_FIXED:
return translateESCVelocity("ESC_PWM_FREQ_FIXED");
return "ESC_PWM_FREQ_FIXED";
case ESC_PWM_FREQ_RAMP:
return translateESCVelocity("ESC_PWM_FREQ_RAMP");
return "ESC_PWM_FREQ_RAMP";
case ESC_PWM_FREQ_OTHER:
return translateESCVelocity("ESC_PWM_FREQ_OTHER");
return "ESC_PWM_FREQ_OTHER";
}
}
@ -214,11 +196,11 @@ const char* ESCTimingAdvanceModes_EnumLabel(int value)
default:
return "";
case ESC_TIMING_ADVANCE_MODE_FIXED:
return translateESCVelocity("ESC_TIMING_ADVANCE_MODE_FIXED");
return "ESC_TIMING_ADVANCE_MODE_FIXED";
case ESC_TIMING_ADVANCE_MODE_RAMP:
return translateESCVelocity("ESC_TIMING_ADVANCE_MODE_RAMP");
return "ESC_TIMING_ADVANCE_MODE_RAMP";
case ESC_TIMING_ADVANCE_MODE_OTHER:
return translateESCVelocity("ESC_TIMING_ADVANCE_MODE_OTHER");
return "ESC_TIMING_ADVANCE_MODE_OTHER";
}
}
@ -236,13 +218,13 @@ const char* ESCProtectionActions_EnumLabel(int value)
default:
return "";
case ESC_PROTECTION_WARNING:
return translateESCVelocity("ESC_PROTECTION_WARNING");
return "ESC_PROTECTION_WARNING";
case ESC_PROTECTION_FOLDBACK:
return translateESCVelocity("ESC_PROTECTION_FOLDBACK");
return "ESC_PROTECTION_FOLDBACK";
case ESC_PROTECTION_DISABLE:
return translateESCVelocity("ESC_PROTECTION_DISABLE");
return "ESC_PROTECTION_DISABLE";
case ESC_PROTECTION_INVALID:
return translateESCVelocity("ESC_PROTECTION_INVALID");
return "ESC_PROTECTION_INVALID";
}
}
@ -260,13 +242,13 @@ const char* ESCBeepModes_EnumLabel(int value)
default:
return "";
case ESC_BEEP_NONE:
return translateESCVelocity("ESC_BEEP_NONE");
return "ESC_BEEP_NONE";
case ESC_BEEP_STATUS:
return translateESCVelocity("ESC_BEEP_STATUS");
return "ESC_BEEP_STATUS";
case ESC_BEEP_ERROR:
return translateESCVelocity("ESC_BEEP_ERROR");
return "ESC_BEEP_ERROR";
case ESC_BEEP_ALL:
return translateESCVelocity("ESC_BEEP_ALL");
return "ESC_BEEP_ALL";
}
}
@ -284,25 +266,27 @@ const char* ESCStandbyCause_EnumLabel(int value)
default:
return "";
case ESC_STANDBY_CAUSE_CMD:
return translateESCVelocity("ESC_STANDBY_CAUSE_CMD");
return "ESC_STANDBY_CAUSE_CMD";
case ESC_STANDBY_CAUSE_INHIBIT:
return translateESCVelocity("ESC_STANDBY_CAUSE_INHIBIT");
return "ESC_STANDBY_CAUSE_INHIBIT";
case ESC_STANDBY_CAUSE_TIMEOUT:
return translateESCVelocity("ESC_STANDBY_CAUSE_TIMEOUT");
return "ESC_STANDBY_CAUSE_TIMEOUT";
case ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR:
return translateESCVelocity("ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR");
return "ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR";
case ESC_STANDBY_CAUSE_INVALID_CMD:
return translateESCVelocity("ESC_STANDBY_CAUSE_INVALID_CMD");
return "ESC_STANDBY_CAUSE_INVALID_CMD";
case ESC_STANDBY_CAUSE_PWM_ARM:
return translateESCVelocity("ESC_STANDBY_CAUSE_PWM_ARM");
return "ESC_STANDBY_CAUSE_PWM_ARM";
case ESC_STANDBY_CAUSE_FAILED_START:
return translateESCVelocity("ESC_STANDBY_CAUSE_FAILED_START");
return "ESC_STANDBY_CAUSE_FAILED_START";
case ESC_STANDBY_CAUSE_MIN_CMD:
return translateESCVelocity("ESC_STANDBY_CAUSE_MIN_CMD");
return "ESC_STANDBY_CAUSE_MIN_CMD";
case ESC_STANDBY_CAUSE_FAILED_RESYNC:
return translateESCVelocity("ESC_STANDBY_CAUSE_FAILED_RESYNC");
return "ESC_STANDBY_CAUSE_FAILED_RESYNC";
case ESC_STANDBY_CAUSE_UNEXPECTED:
return "ESC_STANDBY_CAUSE_UNEXPECTED";
case ESC_STANDBY_CAUSE_RESET:
return translateESCVelocity("ESC_STANDBY_CAUSE_RESET");
return "ESC_STANDBY_CAUSE_RESET";
}
}
@ -320,29 +304,33 @@ const char* ESCDisableCause_EnumLabel(int value)
default:
return "";
case ESC_DISABLE_CAUSE_NONE:
return translateESCVelocity("ESC_DISABLE_CAUSE_NONE");
return "ESC_DISABLE_CAUSE_NONE";
case ESC_DISABLE_CAUSE_CAN_CMD:
return translateESCVelocity("ESC_DISABLE_CAUSE_CAN_CMD");
return "ESC_DISABLE_CAUSE_CAN_CMD";
case ESC_DISABLE_CAUSE_PWM_TIMEOUT:
return translateESCVelocity("ESC_DISABLE_CAUSE_PWM_TIMEOUT");
return "ESC_DISABLE_CAUSE_PWM_TIMEOUT";
case ESC_DISABLE_CAUSE_HARDWARE:
return translateESCVelocity("ESC_DISABLE_CAUSE_HARDWARE");
return "ESC_DISABLE_CAUSE_HARDWARE";
case ESC_DISABLE_CAUSE_OVERCURRENT:
return translateESCVelocity("ESC_DISABLE_CAUSE_OVERCURRENT");
return "ESC_DISABLE_CAUSE_OVERCURRENT";
case ESC_DISABLE_CAUSE_OVERSPEED:
return translateESCVelocity("ESC_DISABLE_CAUSE_OVERSPEED");
return "ESC_DISABLE_CAUSE_OVERSPEED";
case ESC_DISABLE_CAUSE_OVERTEMP:
return translateESCVelocity("ESC_DISABLE_CAUSE_OVERTEMP");
return "ESC_DISABLE_CAUSE_OVERTEMP";
case ESC_DISABLE_CAUSE_UNDERVOLTAGE:
return translateESCVelocity("ESC_DISABLE_CAUSE_UNDERVOLTAGE");
return "ESC_DISABLE_CAUSE_UNDERVOLTAGE";
case ESC_DISABLE_CAUSE_FAILED_START:
return translateESCVelocity("ESC_DISABLE_CAUSE_FAILED_START");
return "ESC_DISABLE_CAUSE_FAILED_START";
case ESC_DISABLE_CAUSE_COMMUTATION_ERROR:
return translateESCVelocity("ESC_DISABLE_CAUSE_COMMUTATION_ERROR");
return "ESC_DISABLE_CAUSE_COMMUTATION_ERROR";
case ESC_DISABLE_CAUSE_PHASE_VOLTAGE:
return "ESC_DISABLE_CAUSE_PHASE_VOLTAGE";
case ESC_DISABLE_CAUSE_REGEN_CURRENT:
return "ESC_DISABLE_CAUSE_REGEN_CURRENT";
case ESC_DISABLE_CAUSE_INVALID_STATE:
return translateESCVelocity("ESC_DISABLE_CAUSE_INVALID_STATE");
return "ESC_DISABLE_CAUSE_INVALID_STATE";
case ESC_DISABLE_CAUSE_RESET:
return translateESCVelocity("ESC_DISABLE_CAUSE_RESET");
return "ESC_DISABLE_CAUSE_RESET";
}
}
@ -360,21 +348,21 @@ const char* ESCMotorOffCause_EnumLabel(int value)
default:
return "";
case ESC_MOTOR_OFF_STANDBY:
return translateESCVelocity("ESC_MOTOR_OFF_STANDBY");
return "ESC_MOTOR_OFF_STANDBY";
case ESC_MOTOR_OFF_BEEP:
return translateESCVelocity("ESC_MOTOR_OFF_BEEP");
return "ESC_MOTOR_OFF_BEEP";
case ESC_MOTOR_OFF_INITIALISE:
return translateESCVelocity("ESC_MOTOR_OFF_INITIALISE");
return "ESC_MOTOR_OFF_INITIALISE";
case ESC_MOTOR_OFF_INHIBITED:
return translateESCVelocity("ESC_MOTOR_OFF_INHIBITED");
return "ESC_MOTOR_OFF_INHIBITED";
case ESC_MOTOR_OFF_THROTTLE_MIN:
return translateESCVelocity("ESC_MOTOR_OFF_THROTTLE_MIN");
return "ESC_MOTOR_OFF_THROTTLE_MIN";
case ESC_MOTOR_OFF_NOT_RUNNING:
return translateESCVelocity("ESC_MOTOR_OFF_NOT_RUNNING");
return "ESC_MOTOR_OFF_NOT_RUNNING";
case ESC_MOTOR_OFF_FAILED_START:
return translateESCVelocity("ESC_MOTOR_OFF_FAILED_START");
return "ESC_MOTOR_OFF_FAILED_START";
case ESC_MOTOR_OFF_INVALID:
return translateESCVelocity("ESC_MOTOR_OFF_INVALID");
return "ESC_MOTOR_OFF_INVALID";
}
}
@ -392,19 +380,19 @@ const char* ESCFailedStartCause_EnumLabel(int value)
default:
return "";
case ESC_FAILED_START_CAUSE_RESET:
return translateESCVelocity("ESC_FAILED_START_CAUSE_RESET");
return "ESC_FAILED_START_CAUSE_RESET";
case ESC_FAILED_START_CAUSE_TIMEOUT:
return translateESCVelocity("ESC_FAILED_START_CAUSE_TIMEOUT");
return "ESC_FAILED_START_CAUSE_TIMEOUT";
case ESC_FAILED_START_CAUSE_OVERSPEED:
return translateESCVelocity("ESC_FAILED_START_CAUSE_OVERSPEED");
return "ESC_FAILED_START_CAUSE_OVERSPEED";
case ESC_FAILED_START_CAUSE_OVERCURRENT:
return translateESCVelocity("ESC_FAILED_START_CAUSE_OVERCURRENT");
return "ESC_FAILED_START_CAUSE_OVERCURRENT";
case ESC_FAILED_START_CAUSE_SPIN_REVERSED:
return translateESCVelocity("ESC_FAILED_START_CAUSE_SPIN_REVERSED");
return "ESC_FAILED_START_CAUSE_SPIN_REVERSED";
case ESC_FAILED_START_CAUSE_SPIN_TOO_FAST:
return translateESCVelocity("ESC_FAILED_START_CAUSE_SPIN_TOO_FAST");
return "ESC_FAILED_START_CAUSE_SPIN_TOO_FAST";
case ESC_FAILED_START_CAUSE_INVALID:
return translateESCVelocity("ESC_FAILED_START_CAUSE_INVALID");
return "ESC_FAILED_START_CAUSE_INVALID";
}
}
@ -422,37 +410,37 @@ const char* ESCMultiCommandPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_SETPOINT_1:
return translateESCVelocity("PKT_ESC_SETPOINT_1");
return "PKT_ESC_SETPOINT_1";
case PKT_ESC_SETPOINT_2:
return translateESCVelocity("PKT_ESC_SETPOINT_2");
return "PKT_ESC_SETPOINT_2";
case PKT_ESC_SETPOINT_3:
return translateESCVelocity("PKT_ESC_SETPOINT_3");
return "PKT_ESC_SETPOINT_3";
case PKT_ESC_SETPOINT_4:
return translateESCVelocity("PKT_ESC_SETPOINT_4");
return "PKT_ESC_SETPOINT_4";
case PKT_ESC_SETPOINT_5:
return translateESCVelocity("PKT_ESC_SETPOINT_5");
return "PKT_ESC_SETPOINT_5";
case PKT_ESC_SETPOINT_6:
return translateESCVelocity("PKT_ESC_SETPOINT_6");
return "PKT_ESC_SETPOINT_6";
case PKT_ESC_SETPOINT_7:
return translateESCVelocity("PKT_ESC_SETPOINT_7");
return "PKT_ESC_SETPOINT_7";
case PKT_ESC_SETPOINT_8:
return translateESCVelocity("PKT_ESC_SETPOINT_8");
return "PKT_ESC_SETPOINT_8";
case PKT_ESC_SETPOINT_9:
return translateESCVelocity("PKT_ESC_SETPOINT_9");
return "PKT_ESC_SETPOINT_9";
case PKT_ESC_SETPOINT_10:
return translateESCVelocity("PKT_ESC_SETPOINT_10");
return "PKT_ESC_SETPOINT_10";
case PKT_ESC_SETPOINT_11:
return translateESCVelocity("PKT_ESC_SETPOINT_11");
return "PKT_ESC_SETPOINT_11";
case PKT_ESC_SETPOINT_12:
return translateESCVelocity("PKT_ESC_SETPOINT_12");
return "PKT_ESC_SETPOINT_12";
case PKT_ESC_SETPOINT_13:
return translateESCVelocity("PKT_ESC_SETPOINT_13");
return "PKT_ESC_SETPOINT_13";
case PKT_ESC_SETPOINT_14:
return translateESCVelocity("PKT_ESC_SETPOINT_14");
return "PKT_ESC_SETPOINT_14";
case PKT_ESC_SETPOINT_15:
return translateESCVelocity("PKT_ESC_SETPOINT_15");
return "PKT_ESC_SETPOINT_15";
case PKT_ESC_SETPOINT_16:
return translateESCVelocity("PKT_ESC_SETPOINT_16");
return "PKT_ESC_SETPOINT_16";
}
}
@ -470,13 +458,15 @@ const char* ESCCommandPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_PWM_CMD:
return translateESCVelocity("PKT_ESC_PWM_CMD");
return "PKT_ESC_PWM_CMD";
case PKT_ESC_RPM_CMD:
return translateESCVelocity("PKT_ESC_RPM_CMD");
return "PKT_ESC_RPM_CMD";
case PKT_ESC_VOLT_CMD:
return "PKT_ESC_VOLT_CMD";
case PKT_ESC_DISABLE:
return translateESCVelocity("PKT_ESC_DISABLE");
return "PKT_ESC_DISABLE";
case PKT_ESC_STANDBY:
return translateESCVelocity("PKT_ESC_STANDBY");
return "PKT_ESC_STANDBY";
}
}
@ -494,15 +484,15 @@ const char* ESCStatusPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_STATUS_A:
return translateESCVelocity("PKT_ESC_STATUS_A");
return "PKT_ESC_STATUS_A";
case PKT_ESC_STATUS_B:
return translateESCVelocity("PKT_ESC_STATUS_B");
return "PKT_ESC_STATUS_B";
case PKT_ESC_STATUS_C:
return translateESCVelocity("PKT_ESC_STATUS_C");
return "PKT_ESC_STATUS_C";
case PKT_ESC_STATUS_D:
return translateESCVelocity("PKT_ESC_STATUS_D");
return "PKT_ESC_STATUS_D";
case PKT_ESC_ACCELEROMETER:
return translateESCVelocity("PKT_ESC_ACCELEROMETER");
return "PKT_ESC_ACCELEROMETER";
}
}
@ -520,75 +510,85 @@ const char* ESCPackets_EnumLabel(int value)
default:
return "";
case PKT_ESC_SYSTEM_CMD:
return translateESCVelocity("PKT_ESC_SYSTEM_CMD");
return "PKT_ESC_SYSTEM_CMD";
case PKT_ESC_SET_TITLE:
return translateESCVelocity("PKT_ESC_SET_TITLE");
return "PKT_ESC_SET_TITLE";
case PKT_ESC_CONTROL_LOOP_DATA:
return translateESCVelocity("PKT_ESC_CONTROL_LOOP_DATA");
return "PKT_ESC_CONTROL_LOOP_DATA";
case PKT_ESC_HALL_SENSOR_INFO:
return "PKT_ESC_HALL_SENSOR_INFO";
case PKT_ESC_WARNINGS_ERRORS:
return translateESCVelocity("PKT_ESC_WARNINGS_ERRORS");
return "PKT_ESC_WARNINGS_ERRORS";
case PKT_ESC_MOTOR_FLAGS:
return translateESCVelocity("PKT_ESC_MOTOR_FLAGS");
return "PKT_ESC_MOTOR_FLAGS";
case PKT_ESC_EVENT:
return translateESCVelocity("PKT_ESC_EVENT");
return "PKT_ESC_EVENT";
case PKT_ESC_SERIAL_NUMBER:
return translateESCVelocity("PKT_ESC_SERIAL_NUMBER");
return "PKT_ESC_SERIAL_NUMBER";
case PKT_ESC_TITLE:
return translateESCVelocity("PKT_ESC_TITLE");
return "PKT_ESC_TITLE";
case PKT_ESC_FIRMWARE:
return translateESCVelocity("PKT_ESC_FIRMWARE");
return "PKT_ESC_FIRMWARE";
case PKT_ESC_SYSTEM_INFO:
return translateESCVelocity("PKT_ESC_SYSTEM_INFO");
return "PKT_ESC_SYSTEM_INFO";
case PKT_ESC_TELEMETRY_SETTINGS:
return translateESCVelocity("PKT_ESC_TELEMETRY_SETTINGS");
return "PKT_ESC_TELEMETRY_SETTINGS";
case PKT_ESC_EEPROM:
return translateESCVelocity("PKT_ESC_EEPROM");
return "PKT_ESC_EEPROM";
case PKT_ESC_EXTRA:
return translateESCVelocity("PKT_ESC_EXTRA");
return "PKT_ESC_EXTRA";
case PKT_ESC_MOTOR_TEMP_SENSOR:
return "PKT_ESC_MOTOR_TEMP_SENSOR";
case PKT_ESC_COMMISSIONING:
return translateESCVelocity("PKT_ESC_COMMISSIONING");
return "PKT_ESC_COMMISSIONING";
case PKT_ESC_TELLTALES:
return translateESCVelocity("PKT_ESC_TELLTALES");
return "PKT_ESC_TELLTALES";
case PKT_ESC_GIT_HASH:
return translateESCVelocity("PKT_ESC_GIT_HASH");
return "PKT_ESC_GIT_HASH";
case PKT_ESC_LEGACY_MOTOR_STATUS:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_STATUS");
return "PKT_ESC_LEGACY_MOTOR_STATUS";
case PKT_ESC_LEGACY_MOTOR_SETTINGS:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_SETTINGS");
return "PKT_ESC_LEGACY_MOTOR_SETTINGS";
case PKT_ESC_LEGACY_MOTOR_SETTINGS_2:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_SETTINGS_2");
return "PKT_ESC_LEGACY_MOTOR_SETTINGS_2";
case PKT_ESC_LEGACY_MOTOR_FIRMWARE:
return translateESCVelocity("PKT_ESC_LEGACY_MOTOR_FIRMWARE");
return "PKT_ESC_LEGACY_MOTOR_FIRMWARE";
case PKT_ESC_MOTOR_SETTINGS:
return translateESCVelocity("PKT_ESC_MOTOR_SETTINGS");
return "PKT_ESC_MOTOR_SETTINGS";
case PKT_ESC_MOTOR_STARTING:
return translateESCVelocity("PKT_ESC_MOTOR_STARTING");
return "PKT_ESC_MOTOR_STARTING";
case PKT_ESC_MOTOR_PARAMETERS:
return translateESCVelocity("PKT_ESC_MOTOR_PARAMETERS");
return "PKT_ESC_MOTOR_PARAMETERS";
case PKT_ESC_MOTOR_HALL_CONFIG:
return "PKT_ESC_MOTOR_HALL_CONFIG";
case PKT_ESC_CONFIG:
return translateESCVelocity("PKT_ESC_CONFIG");
return "PKT_ESC_CONFIG";
case PKT_ESC_WARNINGS:
return translateESCVelocity("PKT_ESC_WARNINGS");
return "PKT_ESC_WARNINGS";
case PKT_ESC_PROTECTION_LEVELS:
return translateESCVelocity("PKT_ESC_PROTECTION_LEVELS");
return "PKT_ESC_PROTECTION_LEVELS";
case PKT_ESC_PROTECTION_ACTIONS:
return translateESCVelocity("PKT_ESC_PROTECTION_ACTIONS");
return "PKT_ESC_PROTECTION_ACTIONS";
case PKT_ESC_VOLT_LOOP_SETTINGS:
return "PKT_ESC_VOLT_LOOP_SETTINGS";
case PKT_ESC_RPM_LOOP_SETTINGS:
return translateESCVelocity("PKT_ESC_RPM_LOOP_SETTINGS");
return "PKT_ESC_RPM_LOOP_SETTINGS";
case PKT_ESC_STARTING_SETTINGS:
return translateESCVelocity("PKT_ESC_STARTING_SETTINGS");
return "PKT_ESC_STARTING_SETTINGS";
case PKT_ESC_CURRENT_CALIBRATION:
return translateESCVelocity("PKT_ESC_CURRENT_CALIBRATION");
return "PKT_ESC_CURRENT_CALIBRATION";
case PKT_ESC_IO_TABLE_SETTINGS:
return translateESCVelocity("PKT_ESC_IO_TABLE_SETTINGS");
return "PKT_ESC_IO_TABLE_SETTINGS";
case PKT_ESC_IO_TABLE_ELEMENT:
return translateESCVelocity("PKT_ESC_IO_TABLE_ELEMENT");
return "PKT_ESC_IO_TABLE_ELEMENT";
case PKT_ESC_THROTTLE_CURVE:
return translateESCVelocity("PKT_ESC_THROTTLE_CURVE");
return "PKT_ESC_THROTTLE_CURVE";
case PKT_ESC_PWM_INPUT_CALIBRATION:
return translateESCVelocity("PKT_ESC_PWM_INPUT_CALIBRATION");
return "PKT_ESC_PWM_INPUT_CALIBRATION";
case PKT_ESC_BULK_TRANSFER:
return translateESCVelocity("PKT_ESC_BULK_TRANSFER");
return "PKT_ESC_BULK_TRANSFER";
case PKT_ESC_DRONECAN_SETTINGS:
return "PKT_ESC_DRONECAN_SETTINGS";
}
}
@ -606,39 +606,93 @@ const char* ESCSystemCommands_EnumLabel(int value)
default:
return "";
case CMD_ESC_SET_NODE_ID:
return translateESCVelocity("CMD_ESC_SET_NODE_ID");
return "CMD_ESC_SET_NODE_ID";
case CMD_ESC_SET_USER_ID_A:
return translateESCVelocity("CMD_ESC_SET_USER_ID_A");
return "CMD_ESC_SET_USER_ID_A";
case CMD_ESC_SET_USER_ID_B:
return translateESCVelocity("CMD_ESC_SET_USER_ID_B");
return "CMD_ESC_SET_USER_ID_B";
case CMD_ESC_TARE_CURRENT:
return translateESCVelocity("CMD_ESC_TARE_CURRENT");
return "CMD_ESC_TARE_CURRENT";
case CMD_ESC_IDENTIFY:
return translateESCVelocity("CMD_ESC_IDENTIFY");
return "CMD_ESC_IDENTIFY";
case CMD_ESC_SET_MOTOR_DIRECTION:
return "CMD_ESC_SET_MOTOR_DIRECTION";
case CMD_ESC_REQUEST_HF_DATA:
return translateESCVelocity("CMD_ESC_REQUEST_HF_DATA");
return "CMD_ESC_REQUEST_HF_DATA";
case CMD_ESC_CONFIGURE_IO_MAP:
return translateESCVelocity("CMD_ESC_CONFIGURE_IO_MAP");
return "CMD_ESC_CONFIGURE_IO_MAP";
case CMD_ESC_CONFIGURE_IO_ELEMENT:
return translateESCVelocity("CMD_ESC_CONFIGURE_IO_ELEMENT");
return "CMD_ESC_CONFIGURE_IO_ELEMENT";
case CMD_ESC_RESET_SETTINGS:
return translateESCVelocity("CMD_ESC_RESET_SETTINGS");
return "CMD_ESC_RESET_SETTINGS";
case CMD_ESC_ENTER_DEBUG:
return translateESCVelocity("CMD_ESC_ENTER_DEBUG");
return "CMD_ESC_ENTER_DEBUG";
case CMD_ESC_EXIT_DEBUG:
return translateESCVelocity("CMD_ESC_EXIT_DEBUG");
return "CMD_ESC_EXIT_DEBUG";
case CMD_ESC_UNLOCK_SETTINGS:
return translateESCVelocity("CMD_ESC_UNLOCK_SETTINGS");
return "CMD_ESC_UNLOCK_SETTINGS";
case CMD_ESC_LOCK_SETTINGS:
return translateESCVelocity("CMD_ESC_LOCK_SETTINGS");
return "CMD_ESC_LOCK_SETTINGS";
case CMD_ESC_VALIDATE_SETTINGS:
return translateESCVelocity("CMD_ESC_VALIDATE_SETTINGS");
return "CMD_ESC_VALIDATE_SETTINGS";
case CMD_ESC_RESET_MOTOR_RUN_TIME:
return translateESCVelocity("CMD_ESC_RESET_MOTOR_RUN_TIME");
return "CMD_ESC_RESET_MOTOR_RUN_TIME";
case CMD_ESC_ENTER_BOOTLOADER:
return translateESCVelocity("CMD_ESC_ENTER_BOOTLOADER");
return "CMD_ESC_ENTER_BOOTLOADER";
case CMD_ESC_RESET:
return translateESCVelocity("CMD_ESC_RESET");
return "CMD_ESC_RESET";
}
}
/*!
* \brief Lookup label for 'CANProtocols' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* CANProtocols_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case CAN_PROTOCOL_PICCOLO:
return "CAN_PROTOCOL_PICCOLO";
case CAN_PROTOCOL_DRONECAN:
return "CAN_PROTOCOL_DRONECAN";
case CAN_PROTOCOL_NONE:
return "CAN_PROTOCOL_NONE";
}
}
/*!
* \brief Lookup label for 'CANBaudRates' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* CANBaudRates_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case CAN_BAUD_RATES_INVALID:
return "CAN_BAUD_RATES_INVALID";
case CAN_BAUD_RATES_1000K:
return "CAN_BAUD_RATES_1000K";
case CAN_BAUD_RATES_500K:
return "CAN_BAUD_RATES_500K";
case CAN_BAUD_RATES_250K:
return "CAN_BAUD_RATES_250K";
case CAN_BAUD_RATES_125K:
return "CAN_BAUD_RATES_125K";
case CAN_BAUD_RATES_100K:
return "CAN_BAUD_RATES_100K";
case CAN_BAUD_RATES_50K:
return "CAN_BAUD_RATES_50K";
}
}

View File

@ -1,4 +1,4 @@
// ESCVelocityProtocol.h was generated by ProtoGen version 3.2.a
// ESCVelocityProtocol.h was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
@ -14,7 +14,7 @@
* 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
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _ESCVELOCITYPROTOCOL_H
@ -37,33 +37,28 @@ extern "C" {
*
* The protocol API enumeration is incremented anytime the protocol is changed
* in a way that affects compatibility with earlier versions of the protocol.
* The protocol enumeration for this version is: 62
* The protocol enumeration for this version is: 88
*
* The protocol version is 3.41
* The protocol version is 3.70
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h> // C string manipulation function header
//! \return the protocol API enumeration
#define getESCVelocityApi() 62
#define getESCVelocityApi() 88
//! \return the protocol version string
#define getESCVelocityVersion() "3.41"
// Translation provided externally. The macro takes a `const char *` and returns a `const char *`
#ifndef translateESCVelocity
#define translateESCVelocity(x) x
#endif
#define getESCVelocityVersion() "3.70"
/*!
* Constant values required for sending a disable (inhibit) command
*/
typedef enum
{
ESC_DISABLE_A = 0xAA,//!< Constant value required for disabling the ESC
ESC_DISABLE_B = 0xC3 //!< Constant value required for disabling the ESC
ESC_DISABLE_A = 0xAA, //!< Constant value required for disabling the ESC
ESC_DISABLE_B = 0xC3 //!< Constant value required for disabling the ESC
} ESCDisableSequence;
/*!
@ -83,6 +78,7 @@ typedef enum
ESC_MODE_STANDBY = 0x00, //!< ESC is in standby mode - the motor is OFF but the ESC is ready to accept motor commands
ESC_MODE_PWM, //!< ESC is controlling motor in open-loop mode based on a 'PWM' (Pulse Width) input
ESC_MODE_RPM, //!< ESC is controlling motor speed based on an RPM setpoint
ESC_MODE_VOLT, //!< ESC is controlling DC voltage based on a provided setpoint
ESC_VALID_MODES //!< ESC mode counter
} ESCOperatingModes;
@ -94,9 +90,9 @@ const char* ESCOperatingModes_EnumLabel(int value);
*/
typedef enum
{
ESC_COMMAND_SOURCE_NONE = 0x00,//!< No valid command has been received
ESC_COMMAND_SOURCE_CAN, //!< Most recent command from CAN
ESC_COMMAND_SOURCE_PWM //!< Most recent command from PWM
ESC_COMMAND_SOURCE_NONE = 0x00, //!< No valid command has been received
ESC_COMMAND_SOURCE_CAN, //!< Most recent command from CAN
ESC_COMMAND_SOURCE_PWM //!< Most recent command from PWM
} ESCCommandSources;
//! \return the label of a 'ESCCommandSources' enum entry, based on its value
@ -107,28 +103,16 @@ const char* ESCCommandSources_EnumLabel(int value);
*/
typedef enum
{
ESC_MOTOR_TEMP_SENSOR_OFF = 0x00,//!< No temperature sensor selected
ESC_MOTOR_TEMP_SENSOR_KTY84, //!< KTY84 or equivalent
ESC_MOTOR_TEMP_SENSOR_KTY83, //!< KTY83 or equivalent
ESC_MOTOR_TEMP_SENSOR_CUSTOM //!< Use a custom temperature lookup table
ESC_MOTOR_TEMP_SENSOR_OFF = 0x00, //!< No temperature sensor selected
ESC_MOTOR_TEMP_SENSOR_KTY84, //!< KTY84 or equivalent
ESC_MOTOR_TEMP_SENSOR_KTY83, //!< KTY83 or equivalent
ESC_MOTOR_TEMP_SENSOR_NTC_SH, //!< NTC sensor (SteinhartHart equation)
ESC_MOTOR_TEMP_SENSOR_NTC_BETA //!< NTC sensor (Beta equation)
} ESCMotorTemperatureSensor;
//! \return the label of a 'ESCMotorTemperatureSensor' enum entry, based on its value
const char* ESCMotorTemperatureSensor_EnumLabel(int value);
/*!
* ESC Command Priorities
*/
typedef enum
{
ESC_COMMAND_PRIORITY_CAN_ONLY = 0x00,//!< Commands only from CAN, PWM hardware input is disabled
ESC_COMMAND_PRIORITY_CAN_PRIORITY, //!< Commands from CAN or PWM hardware input, CAN takes priority
ESC_COMMAND_PRIORITY_PWM_PRIORITY //!< Commands from CAN or PWM hardware input, PWM takes priority
} ESCCommandPriorities;
//! \return the label of a 'ESCCommandPriorities' enum entry, based on its value
const char* ESCCommandPriorities_EnumLabel(int value);
/*!
* Motor direction
*/
@ -147,9 +131,9 @@ const char* ESCMotorDirection_EnumLabel(int value);
*/
typedef enum
{
ESC_HALL_MODE_SENSORLESS = 0, //!< Sensorless control only
ESC_HALL_MODE_SENSORED = 1, //!< Sensored control only
ESC_HALL_MODE_SENSORED_STARTING = 2 //!< Sensored starting transitioning to sensorless running
ESC_HALL_MODE_SENSORLESS = 0, //!< Sensorless control only
ESC_HALL_MODE_SENSORED = 1, //!< Sensored control only
ESC_HALL_MODE_HYBRID = 2 //!< Sensored starting, running below RPM threshold and where sensorless control is unreliable.
} ESCHallSensorMode;
//! \return the label of a 'ESCHallSensorMode' enum entry, based on its value
@ -160,10 +144,10 @@ const char* ESCHallSensorMode_EnumLabel(int value);
*/
typedef enum
{
ESC_AFW_MODE_OFF = 0, //!< AFW always off (during this motor running state)
ESC_AFW_MODE_ON = 1, //!< AFW always on (during this motor running state)
ESC_AFW_MODE_DYNAMIC = 2,//!< AFW may change state
ESC_AFW_MODE_OTHER = 3 //!< Future expansion
ESC_AFW_MODE_OFF = 0, //!< AFW always off (during this motor running state)
ESC_AFW_MODE_ON = 1, //!< AFW always on (during this motor running state)
ESC_AFW_MODE_DYNAMIC = 2, //!< AFW may change state
ESC_AFW_MODE_OTHER = 3 //!< Future expansion
} ESCAFWModes;
//! \return the label of a 'ESCAFWModes' enum entry, based on its value
@ -174,9 +158,9 @@ const char* ESCAFWModes_EnumLabel(int value);
*/
typedef enum
{
ESC_PWM_FREQ_FIXED = 0,//!< PWM frequency is the specified value
ESC_PWM_FREQ_RAMP = 1,
ESC_PWM_FREQ_OTHER = 3 //!< Future expansion
ESC_PWM_FREQ_FIXED = 0, //!< PWM frequency is the specified value
ESC_PWM_FREQ_RAMP = 1,
ESC_PWM_FREQ_OTHER = 3 //!< Future expansion
} ESCPWMFreqModes;
//! \return the label of a 'ESCPWMFreqModes' enum entry, based on its value
@ -187,9 +171,9 @@ const char* ESCPWMFreqModes_EnumLabel(int value);
*/
typedef enum
{
ESC_TIMING_ADVANCE_MODE_FIXED = 0,//!< Timing advance is the specified value
ESC_TIMING_ADVANCE_MODE_RAMP = 1,
ESC_TIMING_ADVANCE_MODE_OTHER = 3 //!< Future expansion
ESC_TIMING_ADVANCE_MODE_FIXED = 0, //!< Timing advance is the specified value
ESC_TIMING_ADVANCE_MODE_RAMP = 1,
ESC_TIMING_ADVANCE_MODE_OTHER = 3 //!< Future expansion
} ESCTimingAdvanceModes;
//! \return the label of a 'ESCTimingAdvanceModes' enum entry, based on its value
@ -214,10 +198,10 @@ const char* ESCProtectionActions_EnumLabel(int value);
*/
typedef enum
{
ESC_BEEP_NONE = 0b00,
ESC_BEEP_STATUS = 0b01,//!< Motor status beeps only
ESC_BEEP_ERROR = 0b10,//!< Motor error beeps only
ESC_BEEP_ALL = 0b11 //!< All motor beeps
ESC_BEEP_NONE = 0b00,
ESC_BEEP_STATUS = 0b01, //!< Motor status beeps only
ESC_BEEP_ERROR = 0b10, //!< Motor error beeps only
ESC_BEEP_ALL = 0b11 //!< All motor beeps
} ESCBeepModes;
//! \return the label of a 'ESCBeepModes' enum entry, based on its value
@ -228,16 +212,17 @@ const char* ESCBeepModes_EnumLabel(int value);
*/
typedef enum
{
ESC_STANDBY_CAUSE_CMD = 0x0001, //!< ESC was put into *STANDBY* mode by a command
ESC_STANDBY_CAUSE_INHIBIT = 0x0002, //!< ESC was put into *STANDBY* mode by SW or HW inhibit
ESC_STANDBY_CAUSE_TIMEOUT = 0x0004, //!< ESC was put into *STANDBY* mode due to keepalive timeout
ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR = 0x0008,//!< ESC was put into *STANDBY* mode due to a hall sensor error
ESC_STANDBY_CAUSE_INVALID_CMD = 0x0010, //!< ESC was put into *STANDBY* mode due to a command being invalid
ESC_STANDBY_CAUSE_PWM_ARM = 0x0020, //!< PWM arming signal detected
ESC_STANDBY_CAUSE_FAILED_START = 0x0040, //!< ESC was put into *STANDBY* mode due to failed starting routine
ESC_STANDBY_CAUSE_MIN_CMD = 0x0080, //!< ESC was put into *STANDBY* mode due to the received command below minimum threshold
ESC_STANDBY_CAUSE_FAILED_RESYNC = 0x0100, //!< ESC was put into *STANDBY* mode due to failed resync routine
ESC_STANDBY_CAUSE_RESET = 0x8000
ESC_STANDBY_CAUSE_CMD = 0x0001, //!< ESC was put into *STANDBY* mode by a command
ESC_STANDBY_CAUSE_INHIBIT = 0x0002, //!< ESC was put into *STANDBY* mode by SW or HW inhibit
ESC_STANDBY_CAUSE_TIMEOUT = 0x0004, //!< ESC was put into *STANDBY* mode due to keepalive timeout
ESC_STANDBY_CAUSE_HALL_SENSOR_ERROR = 0x0008, //!< ESC was put into *STANDBY* mode due to a hall sensor error
ESC_STANDBY_CAUSE_INVALID_CMD = 0x0010, //!< ESC was put into *STANDBY* mode due to a command being invalid
ESC_STANDBY_CAUSE_PWM_ARM = 0x0020, //!< PWM arming signal detected
ESC_STANDBY_CAUSE_FAILED_START = 0x0040, //!< ESC was put into *STANDBY* mode due to failed starting routine
ESC_STANDBY_CAUSE_MIN_CMD = 0x0080, //!< ESC was put into *STANDBY* mode due to the received command below minimum threshold
ESC_STANDBY_CAUSE_FAILED_RESYNC = 0x0100, //!< ESC was put into *STANDBY* mode due to failed resync routine
ESC_STANDBY_CAUSE_UNEXPECTED = 0x0200, //!< ESC was put intot *STANDBY* mode due to an unexpected internal state
ESC_STANDBY_CAUSE_RESET = 0x8000
} ESCStandbyCause;
//! \return the label of a 'ESCStandbyCause' enum entry, based on its value
@ -248,18 +233,20 @@ const char* ESCStandbyCause_EnumLabel(int value);
*/
typedef enum
{
ESC_DISABLE_CAUSE_NONE = 0x0000, //!< Unused / blank value
ESC_DISABLE_CAUSE_CAN_CMD = 0x0001, //!< ESC is disabled by a CAN command
ESC_DISABLE_CAUSE_PWM_TIMEOUT = 0x0002, //!< PWM signal lost
ESC_DISABLE_CAUSE_HARDWARE = 0x0004, //!< Hardware enable signal deasserted
ESC_DISABLE_CAUSE_OVERCURRENT = 0x0008, //!< ESC disabled due to overcurrent
ESC_DISABLE_CAUSE_OVERSPEED = 0x0010, //!< ESC disabled due to overspeed
ESC_DISABLE_CAUSE_OVERTEMP = 0x0020, //!< ESC disabled due to overtemperature
ESC_DISABLE_CAUSE_UNDERVOLTAGE = 0x0040, //!< ESC disabled due to undervoltage
ESC_DISABLE_CAUSE_FAILED_START = 0x0080, //!< ESC disabled due to starting failure (see ESCFailedStartCause for details)
ESC_DISABLE_CAUSE_COMMUTATION_ERROR = 0x0100,//!< ESC disabled due to commutation failure
ESC_DISABLE_CAUSE_INVALID_STATE = 0x2000, //!< ESC disabled due to invalid commutation state
ESC_DISABLE_CAUSE_RESET = 0x8000 //!< ESC is disabled by processor reset
ESC_DISABLE_CAUSE_NONE = 0x0000, //!< Unused / blank value
ESC_DISABLE_CAUSE_CAN_CMD = 0x0001, //!< ESC is disabled by a CAN command
ESC_DISABLE_CAUSE_PWM_TIMEOUT = 0x0002, //!< PWM signal lost
ESC_DISABLE_CAUSE_HARDWARE = 0x0004, //!< Hardware enable signal deasserted
ESC_DISABLE_CAUSE_OVERCURRENT = 0x0008, //!< ESC disabled due to overcurrent
ESC_DISABLE_CAUSE_OVERSPEED = 0x0010, //!< ESC disabled due to overspeed
ESC_DISABLE_CAUSE_OVERTEMP = 0x0020, //!< ESC disabled due to overtemperature
ESC_DISABLE_CAUSE_UNDERVOLTAGE = 0x0040, //!< ESC disabled due to undervoltage
ESC_DISABLE_CAUSE_FAILED_START = 0x0080, //!< ESC disabled due to starting failure (see ESCFailedStartCause for details)
ESC_DISABLE_CAUSE_COMMUTATION_ERROR = 0x0100, //!< ESC disabled due to commutation failure
ESC_DISABLE_CAUSE_PHASE_VOLTAGE = 0x0200, //!< Phase voltage issues detected
ESC_DISABLE_CAUSE_REGEN_CURRENT = 0x0400, //!< Regen current exceeded threshold
ESC_DISABLE_CAUSE_INVALID_STATE = 0x2000, //!< ESC disabled due to invalid commutation state
ESC_DISABLE_CAUSE_RESET = 0x8000 //!< ESC is disabled by processor reset
} ESCDisableCause;
//! \return the label of a 'ESCDisableCause' enum entry, based on its value
@ -288,13 +275,13 @@ const char* ESCMotorOffCause_EnumLabel(int value);
*/
typedef enum
{
ESC_FAILED_START_CAUSE_RESET = 0x0000, //!< No failed start has been recorded
ESC_FAILED_START_CAUSE_TIMEOUT = 0x0001, //!< Starting procedure timed out
ESC_FAILED_START_CAUSE_OVERSPEED = 0x0002, //!< Commutation speed too high
ESC_FAILED_START_CAUSE_OVERCURRENT = 0x0004, //!< Starting current exceeded
ESC_FAILED_START_CAUSE_SPIN_REVERSED = 0x0010,//!< Motor is already spinning, in reverse direction
ESC_FAILED_START_CAUSE_SPIN_TOO_FAST = 0x0020,//!< Motor is already spinning, above maximum catch speed
ESC_FAILED_START_CAUSE_INVALID = 0x8000
ESC_FAILED_START_CAUSE_RESET = 0x0000, //!< No failed start has been recorded
ESC_FAILED_START_CAUSE_TIMEOUT = 0x0001, //!< Starting procedure timed out
ESC_FAILED_START_CAUSE_OVERSPEED = 0x0002, //!< Commutation speed too high
ESC_FAILED_START_CAUSE_OVERCURRENT = 0x0004, //!< Starting current exceeded
ESC_FAILED_START_CAUSE_SPIN_REVERSED = 0x0010, //!< Motor is already spinning, in reverse direction
ESC_FAILED_START_CAUSE_SPIN_TOO_FAST = 0x0020, //!< Motor is already spinning, above maximum catch speed
ESC_FAILED_START_CAUSE_INVALID = 0x8000
} ESCFailedStartCause;
//! \return the label of a 'ESCFailedStartCause' enum entry, based on its value
@ -305,22 +292,22 @@ const char* ESCFailedStartCause_EnumLabel(int value);
*/
typedef enum
{
PKT_ESC_SETPOINT_1 = 0,//!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 1 - 4
PKT_ESC_SETPOINT_2, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 5 - 8
PKT_ESC_SETPOINT_3, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 9 - 12
PKT_ESC_SETPOINT_4, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 13 - 16
PKT_ESC_SETPOINT_5, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 17 - 20
PKT_ESC_SETPOINT_6, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 21 - 24
PKT_ESC_SETPOINT_7, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 25 - 28
PKT_ESC_SETPOINT_8, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 29 - 32
PKT_ESC_SETPOINT_9, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 33 - 36
PKT_ESC_SETPOINT_10, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 37 - 40
PKT_ESC_SETPOINT_11, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 41 - 44
PKT_ESC_SETPOINT_12, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 45 - 48
PKT_ESC_SETPOINT_13, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 49 - 52
PKT_ESC_SETPOINT_14, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 53 - 56
PKT_ESC_SETPOINT_15, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 57 - 60
PKT_ESC_SETPOINT_16 //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 61 - 64
PKT_ESC_SETPOINT_1 = 0, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 1 - 4
PKT_ESC_SETPOINT_2, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 5 - 8
PKT_ESC_SETPOINT_3, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 9 - 12
PKT_ESC_SETPOINT_4, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 13 - 16
PKT_ESC_SETPOINT_5, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 17 - 20
PKT_ESC_SETPOINT_6, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 21 - 24
PKT_ESC_SETPOINT_7, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 25 - 28
PKT_ESC_SETPOINT_8, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 29 - 32
PKT_ESC_SETPOINT_9, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 33 - 36
PKT_ESC_SETPOINT_10, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 37 - 40
PKT_ESC_SETPOINT_11, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 41 - 44
PKT_ESC_SETPOINT_12, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 45 - 48
PKT_ESC_SETPOINT_13, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 49 - 52
PKT_ESC_SETPOINT_14, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 53 - 56
PKT_ESC_SETPOINT_15, //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 57 - 60
PKT_ESC_SETPOINT_16 //!< This packet is used to send commands to multiple ESCs with sequential CAN IDs 61 - 64
} ESCMultiCommandPackets;
//! \return the label of a 'ESCMultiCommandPackets' enum entry, based on its value
@ -331,10 +318,11 @@ const char* ESCMultiCommandPackets_EnumLabel(int value);
*/
typedef enum
{
PKT_ESC_PWM_CMD = 0x10,//!< Send a PWM (Pulse width) command to a particular ESC
PKT_ESC_RPM_CMD, //!< Send an RPM (Speed) command to a particular ESC
PKT_ESC_DISABLE = 0x20,//!< Send this packet to an ESC to disable the ESC
PKT_ESC_STANDBY //!< Send this packet to an ESC to enable the ESC and place it in Standby mode
PKT_ESC_PWM_CMD = 0x10, //!< Send a PWM (Pulse width) command to a particular ESC
PKT_ESC_RPM_CMD, //!< Send an RPM (Speed) command to a particular ESC
PKT_ESC_VOLT_CMD, //!< Send a voltage loop command to a particular ESC
PKT_ESC_DISABLE = 0x20, //!< Send this packet to an ESC to disable the ESC
PKT_ESC_STANDBY //!< Send this packet to an ESC to enable the ESC and place it in Standby mode
} ESCCommandPackets;
//! \return the label of a 'ESCCommandPackets' enum entry, based on its value
@ -345,11 +333,11 @@ const char* ESCCommandPackets_EnumLabel(int value);
*/
typedef enum
{
PKT_ESC_STATUS_A = 0x80, //!< ESC Status A telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_B, //!< ESC Status B telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_C, //!< ESC Status C telemetry packet transmitted by the ESC at regular intervals (reserved for future use)
PKT_ESC_STATUS_D, //!< Currently used for debug only
PKT_ESC_ACCELEROMETER = 0x88 //!< Raw accelerometer data
PKT_ESC_STATUS_A = 0x80, //!< ESC Status A telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_B, //!< ESC Status B telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_C, //!< ESC Status C telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_STATUS_D, //!< ECC Status D telemetry packet transmitted by the ESC at regular intervals
PKT_ESC_ACCELEROMETER = 0x88 //!< Raw accelerometer data
} ESCStatusPackets;
//! \return the label of a 'ESCStatusPackets' enum entry, based on its value
@ -360,41 +348,46 @@ const char* ESCStatusPackets_EnumLabel(int value);
*/
typedef enum
{
PKT_ESC_SYSTEM_CMD = 0x50, //!< Send a configuration command to the ESC (followed by optional command data bytes)
PKT_ESC_SET_TITLE, //!< Set the ESC descriptor title
PKT_ESC_CONTROL_LOOP_DATA = 0x8A, //!< Control loop output data - varies depending on the operational mode of the ESC
PKT_ESC_WARNINGS_ERRORS = 0x86, //!< ESC warning / error status information.
PKT_ESC_MOTOR_FLAGS, //!< Motor status flags
PKT_ESC_EVENT = 0x8D, //!< Event description packet
PKT_ESC_SERIAL_NUMBER = 0x90, //!< ESC Serial Number and User ID information
PKT_ESC_TITLE, //!< Human-readable string descriptor (max 8 chars) of the particular ESC
PKT_ESC_FIRMWARE, //!< ESC Firmware information
PKT_ESC_SYSTEM_INFO, //!< ESC system information packet
PKT_ESC_TELEMETRY_SETTINGS, //!< Telemetry packet configuration
PKT_ESC_EEPROM, //!< ESC non-volatile data information and settings
PKT_ESC_EXTRA, //!< Extra settings
PKT_ESC_COMMISSIONING = 0x99, //!< ESC commissioning data (factory only)
PKT_ESC_TELLTALES, //!< ESC telltales
PKT_ESC_GIT_HASH, //!< ESC firmware git hash
PKT_ESC_LEGACY_MOTOR_STATUS = 0xA0, //!< ESC motor status information
PKT_ESC_LEGACY_MOTOR_SETTINGS = 0xA5,//!< ESC motor configuration
PKT_ESC_LEGACY_MOTOR_SETTINGS_2 = 0xA6,//!< ESC Motor settings information
PKT_ESC_LEGACY_MOTOR_FIRMWARE = 0xAA,//!< ESC motor control firmware information
PKT_ESC_MOTOR_SETTINGS = 0xA7, //!< Motor control settings packet
PKT_ESC_MOTOR_STARTING = 0xA8, //!< Motor starting settings packet
PKT_ESC_MOTOR_PARAMETERS = 0xA9, //!< Motor and system parameters
PKT_ESC_CONFIG = 0xB0, //!< ESC Configuration parameters
PKT_ESC_WARNINGS = 0xB1, //!< Warning level values for various ESC parameters (legacy)
PKT_ESC_PROTECTION_LEVELS = 0xB2, //!< ESC protection values
PKT_ESC_PROTECTION_ACTIONS = 0xB3, //!< ESC protection actions
PKT_ESC_RPM_LOOP_SETTINGS = 0xB5, //!< RPM Control Loop Settings
PKT_ESC_STARTING_SETTINGS, //!< ESC auto-starting configuration for RPM mode
PKT_ESC_CURRENT_CALIBRATION, //!< ESC current sense calibration settings
PKT_ESC_IO_TABLE_SETTINGS = 0xC0, //!< Configuration of the Input/Output mapping
PKT_ESC_IO_TABLE_ELEMENT, //!< A single element of the Input/Output mapping table
PKT_ESC_THROTTLE_CURVE = 0xC2, //!< Throttle curve calibration
PKT_ESC_PWM_INPUT_CALIBRATION = 0xC3,//!< PWM input calibration
PKT_ESC_BULK_TRANSFER = 0xF0 //!< Bulk data transfer (long packets)
PKT_ESC_SYSTEM_CMD = 0x50, //!< Send a configuration command to the ESC (followed by optional command data bytes)
PKT_ESC_SET_TITLE = 0x51, //!< Set the ESC descriptor title
PKT_ESC_CONTROL_LOOP_DATA = 0x8A, //!< Control loop output data - varies depending on the operational mode of the ESC
PKT_ESC_HALL_SENSOR_INFO = 0x8C, //!< Hall sensor information - detected pattern, advance, validity
PKT_ESC_WARNINGS_ERRORS = 0x86, //!< ESC warning / error status information.
PKT_ESC_MOTOR_FLAGS = 0x87, //!< Motor status flags
PKT_ESC_EVENT = 0x8D, //!< Event description packet
PKT_ESC_SERIAL_NUMBER = 0x90, //!< ESC Serial Number and User ID information
PKT_ESC_TITLE = 0x91, //!< Human-readable string descriptor (max 8 chars) of the particular ESC
PKT_ESC_FIRMWARE = 0x92, //!< ESC Firmware information
PKT_ESC_SYSTEM_INFO = 0x93, //!< ESC system information packet
PKT_ESC_TELEMETRY_SETTINGS = 0x94, //!< Telemetry packet configuration
PKT_ESC_EEPROM = 0x95, //!< ESC non-volatile data information and settings
PKT_ESC_EXTRA = 0x96, //!< Extra settings
PKT_ESC_MOTOR_TEMP_SENSOR = 0x97, //!< Motor temperature sensor settings
PKT_ESC_COMMISSIONING = 0x99, //!< ESC commissioning data (factory only)
PKT_ESC_TELLTALES = 0x9A, //!< ESC telltales
PKT_ESC_GIT_HASH = 0x9B, //!< ESC firmware git hash
PKT_ESC_LEGACY_MOTOR_STATUS = 0xA0, //!< ESC motor status information
PKT_ESC_LEGACY_MOTOR_SETTINGS = 0xA5, //!< ESC motor configuration
PKT_ESC_LEGACY_MOTOR_SETTINGS_2 = 0xA6, //!< ESC Motor settings information
PKT_ESC_LEGACY_MOTOR_FIRMWARE = 0xAA, //!< ESC motor control firmware information
PKT_ESC_MOTOR_SETTINGS = 0xA7, //!< Motor control settings packet
PKT_ESC_MOTOR_STARTING = 0xA8, //!< Motor starting settings packet
PKT_ESC_MOTOR_PARAMETERS = 0xA9, //!< Motor and system parameters
PKT_ESC_MOTOR_HALL_CONFIG = 0xAB, //!< Motor hall sensor configuration
PKT_ESC_CONFIG = 0xB0, //!< ESC Configuration parameters
PKT_ESC_WARNINGS = 0xB1, //!< Warning level values for various ESC parameters (legacy)
PKT_ESC_PROTECTION_LEVELS = 0xB2, //!< ESC protection values
PKT_ESC_PROTECTION_ACTIONS = 0xB3, //!< ESC protection actions
PKT_ESC_VOLT_LOOP_SETTINGS = 0xB4, //!< Voltage Control Loop Settings
PKT_ESC_RPM_LOOP_SETTINGS = 0xB5, //!< RPM Control Loop Settings
PKT_ESC_STARTING_SETTINGS = 0xB6, //!< ESC auto-starting configuration for RPM mode
PKT_ESC_CURRENT_CALIBRATION = 0xB7, //!< ESC current sense calibration settings
PKT_ESC_IO_TABLE_SETTINGS = 0xC0, //!< Configuration of the Input/Output mapping
PKT_ESC_IO_TABLE_ELEMENT = 0xC1, //!< A single element of the Input/Output mapping table
PKT_ESC_THROTTLE_CURVE = 0xC2, //!< Throttle curve calibration
PKT_ESC_PWM_INPUT_CALIBRATION = 0xC3, //!< PWM input calibration
PKT_ESC_BULK_TRANSFER = 0xF0, //!< Bulk data transfer (long packets)
PKT_ESC_DRONECAN_SETTINGS = 0xFA //!< DroneCAN specific settings
} ESCPackets;
//! \return the label of a 'ESCPackets' enum entry, based on its value
@ -410,6 +403,7 @@ typedef enum
CMD_ESC_SET_USER_ID_B, //!< Set user ID B value
CMD_ESC_TARE_CURRENT = 0x60, //!< Tare the current measurement
CMD_ESC_IDENTIFY = 0x70, //!< Identify the ESC with a sequence of LED flashes / beeps
CMD_ESC_SET_MOTOR_DIRECTION = 0x90, //!< Set the motor direction
CMD_ESC_REQUEST_HF_DATA = 0xB0, //!< Request high-frequency telemetry data
CMD_ESC_CONFIGURE_IO_MAP = 0xC0, //!< Configure the Input/Output map for the ESC
CMD_ESC_CONFIGURE_IO_ELEMENT, //!< Configure (or request) a particular element of the I/O map
@ -427,6 +421,36 @@ typedef enum
//! \return the label of a 'ESCSystemCommands' enum entry, based on its value
const char* ESCSystemCommands_EnumLabel(int value);
/*!
* ESC CAN Protocols
*/
typedef enum
{
CAN_PROTOCOL_PICCOLO = 0x00, //!< Piccolo CAN protocol
CAN_PROTOCOL_DRONECAN = 0x01, //!< DroneCAN CAN protocol
CAN_PROTOCOL_NONE = 0xFF //!< No protocol specified
} CANProtocols;
//! \return the label of a 'CANProtocols' enum entry, based on its value
const char* CANProtocols_EnumLabel(int value);
/*!
* ESC CAN Baud rates
*/
typedef enum
{
CAN_BAUD_RATES_INVALID = 0x00,
CAN_BAUD_RATES_1000K,
CAN_BAUD_RATES_500K,
CAN_BAUD_RATES_250K,
CAN_BAUD_RATES_125K,
CAN_BAUD_RATES_100K,
CAN_BAUD_RATES_50K
} CANBaudRates;
//! \return the label of a 'CANBaudRates' enum entry, based on its value
const char* CANBaudRates_EnumLabel(int value);
// The prototypes below provide an interface to the packets.
// They are not auto-generated functions, but must be hand-written

View File

@ -1,281 +0,0 @@
// LegacyESCDefines.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 "LegacyESCDefines.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Encode a ESC_LegacyStatusBits_t into a byte array
*
* Status bits associated with the legacy (gen-1) ESC
* \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_LegacyStatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_LegacyStatusBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = Hardware inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->hwInhibit << 7;
// 1 = Software inhibit is active (ESC is disabled)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->swInhibit << 6;
// 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->afwEnabled << 5;
// 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->direction << 4;
// Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->timeout << 3;
// 1 = in starting mode (0 = stopped or running)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->starting << 2;
// 0 = most recent command from CAN, 1 = most recent command from PWM
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->commandSource << 1;
// ESC is running
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->running;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_LegacyStatusBits_t
/*!
* \brief Decode a ESC_LegacyStatusBits_t from a byte array
*
* Status bits associated with the legacy (gen-1) ESC
* \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_LegacyStatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_LegacyStatusBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// 1 = Hardware inhibit is active (ESC is disabled)
_pg_user->hwInhibit = (_pg_data[_pg_byteindex] >> 7);
// 1 = Software inhibit is active (ESC is disabled)
_pg_user->swInhibit = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
_pg_user->afwEnabled = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
_pg_user->direction = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
_pg_user->timeout = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// 1 = in starting mode (0 = stopped or running)
_pg_user->starting = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// 0 = most recent command from CAN, 1 = most recent command from PWM
_pg_user->commandSource = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// ESC is running
_pg_user->running = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_LegacyStatusBits_t
/*!
* \brief Encode a ESC_LegacyWarningBits_t into a byte array
*
* Warning bits associated with the legacy (gen-1) ESC
* \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_LegacyWarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_LegacyWarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if RPM signal is not detected
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->noRPMSignal << 7;
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overspeed << 6;
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overcurrent << 5;
// Set if the internal ESC temperature is above the warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->escTemperature << 4;
// Set if the motor temperature is above the warning threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->motorTemperature << 3;
// Set if the input voltage is below the minimum threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->undervoltage << 2;
// Set if the input voltage is above the maximum threshold
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->overvoltage << 1;
// Set if hardware PWM input is enabled but invalid
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->invalidPWMsignal;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_LegacyWarningBits_t
/*!
* \brief Decode a ESC_LegacyWarningBits_t from a byte array
*
* Warning bits associated with the legacy (gen-1) ESC
* \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_LegacyWarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_LegacyWarningBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if RPM signal is not detected
_pg_user->noRPMSignal = (_pg_data[_pg_byteindex] >> 7);
// Set if the ESC motor speed exceeds the configured warning threshold
_pg_user->overspeed = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
_pg_user->overcurrent = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// Set if the internal ESC temperature is above the warning threshold
_pg_user->escTemperature = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Set if the motor temperature is above the warning threshold
_pg_user->motorTemperature = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// Set if the input voltage is below the minimum threshold
_pg_user->undervoltage = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// Set if the input voltage is above the maximum threshold
_pg_user->overvoltage = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// Set if hardware PWM input is enabled but invalid
_pg_user->invalidPWMsignal = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_LegacyWarningBits_t
/*!
* \brief Encode a ESC_LegacyErrorBits_t into a byte array
*
* Error bits associated with the legacy (gen-1) ESC
* \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_LegacyErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_LegacyErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if communication link to the motor controller is lost
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->linkError << 7;
// Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->foldback << 6;
// Set if the settings checksum does not match the programmed values
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->settingsChecksum << 5;
// Set if the motor settings are invalid
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->motorSettings << 4;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedD << 3;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedE << 2;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedF << 1;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedG;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_LegacyErrorBits_t
/*!
* \brief Decode a ESC_LegacyErrorBits_t from a byte array
*
* Error bits associated with the legacy (gen-1) ESC
* \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_LegacyErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_LegacyErrorBits_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// Set if communication link to the motor controller is lost
_pg_user->linkError = (_pg_data[_pg_byteindex] >> 7);
// Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
_pg_user->foldback = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// Set if the settings checksum does not match the programmed values
_pg_user->settingsChecksum = ((_pg_data[_pg_byteindex] >> 5) & 0x1);
// Set if the motor settings are invalid
_pg_user->motorSettings = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// Reserved for future use
_pg_user->reservedD = ((_pg_data[_pg_byteindex] >> 3) & 0x1);
// Reserved for future use
_pg_user->reservedE = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// Reserved for future use
_pg_user->reservedF = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// Reserved for future use
_pg_user->reservedG = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_LegacyErrorBits_t
// end of LegacyESCDefines.c

View File

@ -1,119 +0,0 @@
// LegacyESCDefines.h 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
*/
#ifndef _LEGACYESCDEFINES_H
#define _LEGACYESCDEFINES_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
/*!
* Status bits associated with the legacy (gen-1) ESC
*/
typedef struct
{
unsigned hwInhibit : 1; //!< 1 = Hardware inhibit is active (ESC is disabled)
unsigned swInhibit : 1; //!< 1 = Software inhibit is active (ESC is disabled)
unsigned afwEnabled : 1; //!< 0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled
unsigned direction : 1; //!< 0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE
unsigned timeout : 1; //!< Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)
unsigned starting : 1; //!< 1 = in starting mode (0 = stopped or running)
unsigned commandSource : 1; //!< 0 = most recent command from CAN, 1 = most recent command from PWM
unsigned running : 1; //!< ESC is running
}ESC_LegacyStatusBits_t;
//! return the minimum encoded length for the ESC_LegacyStatusBits_t structure
#define getMinLengthOfESC_LegacyStatusBits_t() (1)
//! return the maximum encoded length for the ESC_LegacyStatusBits_t structure
#define getMaxLengthOfESC_LegacyStatusBits_t() (1)
//! Encode a ESC_LegacyStatusBits_t into a byte array
void encodeESC_LegacyStatusBits_t(uint8_t* data, int* bytecount, const ESC_LegacyStatusBits_t* user);
//! Decode a ESC_LegacyStatusBits_t from a byte array
int decodeESC_LegacyStatusBits_t(const uint8_t* data, int* bytecount, ESC_LegacyStatusBits_t* user);
/*!
* Warning bits associated with the legacy (gen-1) ESC
*/
typedef struct
{
unsigned noRPMSignal : 1; //!< Set if RPM signal is not detected
unsigned overspeed : 1; //!< Set if the ESC motor speed exceeds the configured warning threshold
unsigned overcurrent : 1; //!< Set if the ESC motor current (positive or negative) exceeds the configured warning threshold
unsigned escTemperature : 1; //!< Set if the internal ESC temperature is above the warning threshold
unsigned motorTemperature : 1; //!< Set if the motor temperature is above the warning threshold
unsigned undervoltage : 1; //!< Set if the input voltage is below the minimum threshold
unsigned overvoltage : 1; //!< Set if the input voltage is above the maximum threshold
unsigned invalidPWMsignal : 1; //!< Set if hardware PWM input is enabled but invalid
}ESC_LegacyWarningBits_t;
//! return the minimum encoded length for the ESC_LegacyWarningBits_t structure
#define getMinLengthOfESC_LegacyWarningBits_t() (1)
//! return the maximum encoded length for the ESC_LegacyWarningBits_t structure
#define getMaxLengthOfESC_LegacyWarningBits_t() (1)
//! Encode a ESC_LegacyWarningBits_t into a byte array
void encodeESC_LegacyWarningBits_t(uint8_t* data, int* bytecount, const ESC_LegacyWarningBits_t* user);
//! Decode a ESC_LegacyWarningBits_t from a byte array
int decodeESC_LegacyWarningBits_t(const uint8_t* data, int* bytecount, ESC_LegacyWarningBits_t* user);
/*!
* Error bits associated with the legacy (gen-1) ESC
*/
typedef struct
{
unsigned linkError : 1; //!< Set if communication link to the motor controller is lost
unsigned foldback : 1; //!< Set if the ESC has detected an overcurrent event and is actively folding back duty cycle
unsigned settingsChecksum : 1; //!< Set if the settings checksum does not match the programmed values
unsigned motorSettings : 1; //!< Set if the motor settings are invalid
unsigned reservedD : 1; //!< Reserved for future use
unsigned reservedE : 1; //!< Reserved for future use
unsigned reservedF : 1; //!< Reserved for future use
unsigned reservedG : 1; //!< Reserved for future use
}ESC_LegacyErrorBits_t;
//! return the minimum encoded length for the ESC_LegacyErrorBits_t structure
#define getMinLengthOfESC_LegacyErrorBits_t() (1)
//! return the maximum encoded length for the ESC_LegacyErrorBits_t structure
#define getMaxLengthOfESC_LegacyErrorBits_t() (1)
//! Encode a ESC_LegacyErrorBits_t into a byte array
void encodeESC_LegacyErrorBits_t(uint8_t* data, int* bytecount, const ESC_LegacyErrorBits_t* user);
//! Decode a ESC_LegacyErrorBits_t from a byte array
int decodeESC_LegacyErrorBits_t(const uint8_t* data, int* bytecount, ESC_LegacyErrorBits_t* user);
#ifdef __cplusplus
}
#endif
#endif // _LEGACYESCDEFINES_H

View File

@ -1,134 +0,0 @@
// LegacyESCPackets.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 "LegacyESCPackets.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Create the ESC_LegacyStatusA packet
*
* Legacy (gen-1) definition for the STATUS_A packet
* \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 3 bits are used for debugging and should be ignored for general use.
* \param status is ESC status bits
* \param warnings is ESC warning bits
* \param errors is ESC *error* bits
* \param command is ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
* \param rpm is Motor speed
*/
void encodeESC_LegacyStatusAPacket(void* _pg_pkt, uint8_t mode, const ESC_LegacyStatusBits_t* status, const ESC_LegacyWarningBits_t* warnings, const ESC_LegacyErrorBits_t* errors, uint16_t command, uint16_t rpm)
{
uint8_t* _pg_data = getESCVelocityPacketData(_pg_pkt);
int _pg_byteindex = 0;
// Set to 0 to indicate a Gen-2 ESC
_pg_data[_pg_byteindex] = 0;
// ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
// Range of mode is 0 to 127.
_pg_data[_pg_byteindex] |= (uint8_t)limitMax(mode, 127);
_pg_byteindex += 1; // close bit field
// ESC status bits
encodeESC_LegacyStatusBits_t(_pg_data, &_pg_byteindex, status);
// ESC warning bits
encodeESC_LegacyWarningBits_t(_pg_data, &_pg_byteindex, warnings);
// ESC *error* bits
encodeESC_LegacyErrorBits_t(_pg_data, &_pg_byteindex, errors);
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
// 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_LegacyStatusAPacketID());
}// encodeESC_LegacyStatusAPacket
/*!
* \brief Decode the ESC_LegacyStatusA packet
*
* Legacy (gen-1) definition for the STATUS_A packet
* \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 3 bits are used for debugging and should be ignored for general use.
* \param status receives ESC status bits
* \param warnings receives ESC warning bits
* \param errors receives ESC *error* bits
* \param command receives ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
* \param rpm receives Motor speed
* \return 0 is returned if the packet ID or size is wrong, else 1
*/
int decodeESC_LegacyStatusAPacket(const void* _pg_pkt, uint8_t* mode, ESC_LegacyStatusBits_t* status, ESC_LegacyWarningBits_t* warnings, ESC_LegacyErrorBits_t* errors, 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_LegacyStatusAPacketID())
return 0;
if(_pg_numbytes < getESC_LegacyStatusAMinDataLength())
return 0;
// Set to 0 to indicate a Gen-2 ESC
_pg_tempbitfield = (_pg_data[_pg_byteindex] >> 7);
// Decoded value must be 0
if(_pg_tempbitfield != 0)
return 0;
// ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
// Range of mode is 0 to 127.
(*mode) = ((_pg_data[_pg_byteindex]) & 0x7F);
_pg_byteindex += 1; // close bit field
// ESC status bits
if(decodeESC_LegacyStatusBits_t(_pg_data, &_pg_byteindex, status) == 0)
return 0;
// ESC warning bits
if(decodeESC_LegacyWarningBits_t(_pg_data, &_pg_byteindex, warnings) == 0)
return 0;
// ESC *error* bits
if(decodeESC_LegacyErrorBits_t(_pg_data, &_pg_byteindex, errors) == 0)
return 0;
// ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
// 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_LegacyStatusAPacket
// end of LegacyESCPackets.c

View File

@ -1,67 +0,0 @@
// LegacyESCPackets.h 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
*/
#ifndef _LEGACYESCPACKETS_H
#define _LEGACYESCPACKETS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdbool.h>
#include "ESCVelocityProtocol.h"
#include "LegacyESCDefines.h"
/*!
* Legacy (gen-1) definition for the STATUS_A packet
*/
typedef struct
{
uint8_t mode; //!< ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper 3 bits are used for debugging and should be ignored for general use.
ESC_LegacyStatusBits_t status; //!< ESC status bits
ESC_LegacyWarningBits_t warnings; //!< ESC warning bits
ESC_LegacyErrorBits_t errors; //!< ESC *error* bits
uint16_t command; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
}ESC_LegacyStatusA_t;
//! Create the ESC_LegacyStatusA packet from parameters
void encodeESC_LegacyStatusAPacket(void* pkt, uint8_t mode, const ESC_LegacyStatusBits_t* status, const ESC_LegacyWarningBits_t* warnings, const ESC_LegacyErrorBits_t* errors, uint16_t command, uint16_t rpm);
//! Decode the ESC_LegacyStatusA packet to parameters
int decodeESC_LegacyStatusAPacket(const void* pkt, uint8_t* mode, ESC_LegacyStatusBits_t* status, ESC_LegacyWarningBits_t* warnings, ESC_LegacyErrorBits_t* errors, uint16_t* command, uint16_t* rpm);
//! return the packet ID for the ESC_LegacyStatusA packet
#define getESC_LegacyStatusAPacketID() (PKT_ESC_STATUS_A)
//! return the minimum encoded length for the ESC_LegacyStatusA packet
#define getESC_LegacyStatusAMinDataLength() (8)
//! return the maximum encoded length for the ESC_LegacyStatusA packet
#define getESC_LegacyStatusAMaxDataLength() (8)
#ifdef __cplusplus
}
#endif
#endif // _LEGACYESCPACKETS_H