AP_PiccoloCAN: added support for Piccolo CAN ESCs

This commit is contained in:
Oliver Walters 2019-12-09 15:30:58 +11:00 committed by Andrew Tridgell
parent 1248519b11
commit ace0006a4e
20 changed files with 6258 additions and 0 deletions

View File

@ -0,0 +1,624 @@
/*
* 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 <AP_HAL/AP_HAL.h>
#include <AP_AHRS/AP_AHRS.h>
#if HAL_WITH_UAVCAN
#include "AP_PiccoloCAN.h"
#include <uavcan/uavcan.hpp>
#include <uavcan/driver/can.hpp>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Common/AP_Common.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_HAL/utility/sparse-endian.h>
#include <SRV_Channel/SRV_Channel.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <stdio.h>
#include <AP_PiccoloCAN/piccolo_protocol/ESCVelocityProtocol.h>
#include <AP_PiccoloCAN/piccolo_protocol/ESCPackets.h>
extern const AP_HAL::HAL& hal;
static const uint8_t CAN_IFACE_INDEX = 0;
#define debug_can(level_debug, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(_driver_index)) { printf(fmt, ##args); }} while (0)
AP_PiccoloCAN::AP_PiccoloCAN()
{
debug_can(2, "PiccoloCAN: constructed\n\r");
}
AP_PiccoloCAN *AP_PiccoloCAN::get_pcan(uint8_t driver_index)
{
if (driver_index >= AP::can().get_num_drivers() ||
AP::can().get_protocol_type(driver_index) != AP_BoardConfig_CAN::Protocol_Type_PiccoloCAN) {
return nullptr;
}
return static_cast<AP_PiccoloCAN*>(AP::can().get_driver(driver_index));
}
// initialize PiccoloCAN bus
void AP_PiccoloCAN::init(uint8_t driver_index, bool enable_filters)
{
_driver_index = driver_index;
debug_can(2, "PiccoloCAN: starting init\n\r");
if (_initialized) {
debug_can(1, "PiccoloCAN: already initialized\n\r");
return;
}
AP_HAL::CANManager* can_mgr = hal.can_mgr[driver_index];
if (can_mgr == nullptr) {
debug_can(1, "PiccoloCAN: no mgr for this driver\n\r");
return;
}
if (!can_mgr->is_initialized()) {
debug_can(1, "PiccoloCAN: mgr not initialized\n\r");
return;
}
_can_driver = can_mgr->get_driver();
if (_can_driver == nullptr) {
debug_can(1, "PiccoloCAN: no CAN driver\n\r");
return;
}
// start calls to loop in separate thread
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_PiccoloCAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_MAIN, 1)) {
debug_can(1, "PiccoloCAN: couldn't create thread\n\r");
return;
}
_initialized = true;
snprintf(_thread_name, sizeof(_thread_name), "PiccoloCAN_%u", driver_index);
debug_can(2, "PiccoloCAN: init done\n\r");
}
// loop to send output to CAN devices in background thread
void AP_PiccoloCAN::loop()
{
uavcan::CanFrame txFrame;
uavcan::CanFrame rxFrame;
// How often to transmit CAN messages (milliseconds)
#define CMD_TX_PERIOD 10
uint16_t txCounter = 0;
// CAN Frame ID components
uint8_t frame_id_group; // Piccolo message group
uint16_t frame_id_device; // Device identifier
uavcan::MonotonicTime timeout;
while (true) {
if (!_initialized) {
debug_can(2, "PiccoloCAN: not initialized\n\r");
hal.scheduler->delay_microseconds(10000);
continue;
}
timeout = uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 250);
// 1ms loop delay
hal.scheduler->delay_microseconds(1 * 1000);
// Transmit CAN commands at regular intervals
if (txCounter++ > CMD_TX_PERIOD) {
txCounter = 0;
// Transmit ESC commands
send_esc_messages();
}
// Look for any message responses on the CAN bus
while (read_frame(rxFrame, timeout)) {
frame_id_group = (rxFrame.id >> 24) & 0x1F;
frame_id_device = (rxFrame.id >> 8) & 0xFF;
// Only accept extended messages
if ((rxFrame.id & uavcan::CanFrame::FlagEFF) == 0) {
continue;
}
switch (MessageGroup(frame_id_group)) {
// ESC messages exist in the ACTUATOR group
case MessageGroup::ACTUATOR:
switch (ActuatorType(frame_id_device)) {
case ActuatorType::ESC:
if (handle_esc_message(rxFrame)) {
// Returns true if the message was successfully decoded
}
break;
default:
// Unknown actuator type
break;
}
break;
default:
break;
}
}
}
}
// write frame on CAN bus, returns true on success
bool AP_PiccoloCAN::write_frame(uavcan::CanFrame &out_frame, uavcan::MonotonicTime timeout)
{
if (!_initialized) {
debug_can(1, "PiccoloCAN: Driver not initialized for write_frame\n\r");
return false;
}
// wait for space in buffer to send command
uavcan::CanSelectMasks inout_mask;
do {
inout_mask.read = 0;
inout_mask.write = (1 << CAN_IFACE_INDEX);
_select_frames[CAN_IFACE_INDEX] = &out_frame;
_can_driver->select(inout_mask, _select_frames, timeout);
if (!inout_mask.write) {
hal.scheduler->delay_microseconds(50);
}
} while (!inout_mask.write);
return (_can_driver->getIface(CAN_IFACE_INDEX)->send(out_frame, timeout, uavcan::CanIOFlagAbortOnError) == 1);
}
// read frame on CAN bus, returns true on succses
bool AP_PiccoloCAN::read_frame(uavcan::CanFrame &recv_frame, uavcan::MonotonicTime timeout)
{
if (!_initialized) {
debug_can(1, "PiccoloCAN: Driver not initialized for read_frame\n\r");
return false;
}
uavcan::CanSelectMasks inout_mask;
inout_mask.read = 1 << CAN_IFACE_INDEX;
inout_mask.write = 0;
_select_frames[CAN_IFACE_INDEX] = &recv_frame;
_can_driver->select(inout_mask, _select_frames, timeout);
if (!inout_mask.read) {
// No frame available
return false;
}
uavcan::MonotonicTime time;
uavcan::UtcTime utc_time;
uavcan::CanIOFlags flags {};
return (_can_driver->getIface(CAN_IFACE_INDEX)->receive(recv_frame, time, utc_time, flags) == 1);
}
// called from SRV_Channels
void AP_PiccoloCAN::update()
{
uint64_t timestamp = AP_HAL::micros64();
/* Read out the ESC commands from the channel mixer */
for (uint8_t i = 0; i < PICCOLO_CAN_MAX_NUM_ESC; i++) {
// Check each channel to determine if a motor function is assigned
SRV_Channel::Aux_servo_function_t motor_function = SRV_Channels::get_motor_function(i);
if (SRV_Channels::function_assigned(motor_function)) {
uint16_t output = 0;
if (SRV_Channels::get_output_pwm(motor_function, output)) {
_esc_info[i].command = output;
_esc_info[i].newCommand = true;
}
}
}
AP_Logger *logger = AP_Logger::get_singleton();
// Push received telemtry data into the logging system
if (logger && logger->logging_enabled()) {
WITH_SEMAPHORE(_telem_sem);
for (uint8_t i = 0; i < PICCOLO_CAN_MAX_NUM_ESC; i++) {
PiccoloESC_Info_t &esc = _esc_info[i];
if (esc.newTelemetry) {
logger->Write_ESC(i, timestamp,
(int32_t) esc.statusA.rpm * 100,
esc.statusB.voltage,
esc.statusB.current,
(int16_t) esc.statusB.escTemperature,
0, // TODO - Accumulated current
(int16_t) esc.statusB.motorTemperature);
esc.newTelemetry = false;
}
}
}
}
// send ESC telemetry messages over MAVLink
void AP_PiccoloCAN::send_esc_telemetry_mavlink(uint8_t mav_chan)
{
// Arrays to store ESC telemetry data
uint8_t temperature[4] {};
uint16_t voltage[4] {};
uint16_t rpm[4] {};
uint16_t count[4] {};
uint16_t current[4] {};
uint16_t totalcurrent[4] {};
bool dataAvailable = false;
uint8_t idx = 0;
WITH_SEMAPHORE(_telem_sem);
for (uint8_t ii = 0; ii < PICCOLO_CAN_MAX_NUM_ESC; ii++) {
// Calculate index within storage array
idx = (ii % 4);
PiccoloESC_Info_t &esc = _esc_info[idx];
// Has the ESC been heard from recently?
if (is_esc_present(ii)) {
dataAvailable = true;
temperature[idx] = esc.statusB.escTemperature;
voltage[idx] = esc.statusB.voltage;
current[idx] = esc.statusB.current;
totalcurrent[idx] = 0;
rpm[idx] = esc.statusA.rpm;
count[idx] = 0;
} else {
temperature[idx] = 0;
voltage[idx] = 0;
current[idx] = 0;
totalcurrent[idx] = 0;
rpm[idx] = 0;
count[idx] = 0;
}
// Send ESC telemetry in groups of 4
if ((ii % 4) == 3) {
if (dataAvailable) {
if (!HAVE_PAYLOAD_SPACE((mavlink_channel_t) mav_chan, ESC_TELEMETRY_1_TO_4)) {
continue;
}
switch (ii) {
case 3:
mavlink_msg_esc_telemetry_1_to_4_send((mavlink_channel_t) mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
break;
case 7:
mavlink_msg_esc_telemetry_5_to_8_send((mavlink_channel_t) mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
break;
case 11:
mavlink_msg_esc_telemetry_9_to_12_send((mavlink_channel_t) mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
break;
default:
break;
}
}
dataAvailable = false;
}
}
}
// send ESC messages over CAN
void AP_PiccoloCAN::send_esc_messages(void)
{
uavcan::CanFrame txFrame;
uavcan::MonotonicTime timeout = uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 250);
// TODO - How to buffer CAN messages properly?
// Sending more than 2 messages at each loop instance means that sometimes messages are dropped
if (hal.util->get_soft_armed()) {
#define BULK_ESC_COMMANDS
#ifdef BULK_ESC_COMMANDS
bool esc_present = false;
int16_t cmd[4];
uint8_t idx;
// Transmit bulk command packets to 4x ESC simultaneously
for (uint8_t ii = 0; ii < PICCOLO_CAN_MAX_GROUP_ESC; ii++) {
esc_present = false;
for (uint8_t jj = 0; jj < 4; jj++) {
idx = (ii * 4) + jj;
if (_esc_info[idx].newCommand) {
esc_present = true;
cmd[jj] = _esc_info[idx].command;
_esc_info[idx].newCommand = false;
} else {
cmd[jj] = 0xFFFF;
}
}
if (esc_present) {
encodeESC_CommandMultipleESCsPacket(
&txFrame,
cmd[0],
cmd[1],
cmd[2],
cmd[3],
(PKT_ESC_SETPOINT_1 + ii)
);
// Broadcast the command to all ESCs
txFrame.id |= 0xFF;
write_frame(txFrame, timeout);
}
}
#else
// Send an individual command to each configured ESC channel
for (uint8_t i = 0; i < PICCOLO_CAN_MAX_NUM_ESC; i++) {
if (_esc_info[i].newCommand) {
encodeESC_PWMCommandPacket(&txFrame, _esc_info[i].command);
// Set the address
txFrame.id &= ~0xFF;
txFrame.id |= (i + 1);
write_frame(txFrame, timeout);
_esc_info[i].newCommand = false;
}
}
#endif //BULK_ESC_COMMANDS
} else {
// TODO - Change this behavior but for now broadcast a 0% command
encodeESC_PWMCommandPacket(&txFrame, 900);
txFrame.id |= 0xFF;
write_frame(txFrame, timeout);
}
}
// interpret an ESC message received over CAN
bool AP_PiccoloCAN::handle_esc_message(uavcan::CanFrame &frame)
{
uint64_t timestamp = AP_HAL::micros64();
// The ESC address is the lower byte of the address
uint8_t addr = frame.id & 0xFF;
// Ignore any ESC with node ID of zero
if (addr == 0x00) {
return false;
}
// Subtract to get the address in memory
addr -= 1;
// Maximum number of ESCs allowed
if (addr >= PICCOLO_CAN_MAX_NUM_ESC) {
return false;
}
PiccoloESC_Info_t &esc = _esc_info[addr];
bool result = true;
// Throw the packet against each decoding routine
if (decodeESC_StatusAPacketStructure(&frame, &esc.statusA)) {
esc.newTelemetry = true;
} else if (decodeESC_StatusBPacketStructure(&frame, &esc.statusB)) {
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;
}
return result;
}
bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint64_t timeout_ms)
{
if (chan >= PICCOLO_CAN_MAX_NUM_ESC) {
return false;
}
PiccoloESC_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 * 1000;
if (now > (esc.last_rx_msg_timestamp + timeout_us)) {
return false;
}
return true;
}
bool AP_PiccoloCAN::pre_arm_check(char* reason, uint8_t reason_len)
{
// Check that each required ESC is present on the bus
for (uint8_t ii = 0; ii < PICCOLO_CAN_MAX_NUM_ESC; ii++) {
SRV_Channel::Aux_servo_function_t motor_function = SRV_Channels::get_motor_function(ii);
// There is a motor function assigned to this channel
if (SRV_Channels::function_assigned(motor_function)) {
if (!is_esc_present(ii)) {
snprintf(reason, reason_len, "PiccoloCAN: ESC %u not detected", ii + 1);
return false;
}
PiccoloESC_Info_t &esc = _esc_info[ii];
if (esc.statusA.status.hwInhibit) {
snprintf(reason, reason_len, "PiccoloCAN: ESC %u is hardware inhibited", (ii + 1));
return false;
}
if (esc.statusA.status.swInhibit) {
snprintf(reason, reason_len, "PiccoloCAN: ESC %u is software inhibited", (ii + 1));
return false;
}
// TODO - Check each ESC for further error information
}
}
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)
{
uavcan::CanFrame* frame = (uavcan::CanFrame*) pkt;
return (uint8_t*) frame->data;
}
//! \return the packet data pointer from the packet, const
const uint8_t* getESCVelocityPacketDataConst(const void* pkt)
{
uavcan::CanFrame* frame = (uavcan::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)
{
uavcan::CanFrame* frame = (uavcan::CanFrame*) pkt;
if (size > uavcan::CanFrame::MaxDataLen) {
size = uavcan::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 |= uavcan::CanFrame::FlagEFF;
frame->id = id;
}
//! \return the size of a packet from the packet header
int getESCVelocityPacketSize(const void* pkt)
{
uavcan::CanFrame* frame = (uavcan::CanFrame*) pkt;
return (int) frame->dlc;
}
//! \return the ID of a packet from the packet header
uint32_t getESCVelocityPacketID(const void* pkt)
{
uavcan::CanFrame* frame = (uavcan::CanFrame*) pkt;
// Extract the message ID field from the 29-bit ID
return (uint32_t) ((frame->id >> 16) & 0xFF);
}
#endif // HAL_WITH_UAVCAN

View File

@ -0,0 +1,120 @@
/*
* 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
*/
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/CAN.h>
#include <AP_HAL/Semaphores.h>
#include "piccolo_protocol/ESCPackets.h"
// maximum number of ESC allowed on CAN bus simultaneously
#define PICCOLO_CAN_MAX_NUM_ESC 12
#define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4)
class AP_PiccoloCAN : public AP_HAL::CANProtocol
{
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 */
AP_PiccoloCAN(const AP_PiccoloCAN &other) = delete;
AP_PiccoloCAN &operator=(const AP_PiccoloCAN&) = delete;
// Return PiccoloCAN from @driver_index or nullptr if it's not ready or doesn't exist
static AP_PiccoloCAN *get_pcan(uint8_t driver_index);
// initialize PiccoloCAN bus
void init(uint8_t driver_index, bool enable_filters) override;
// called from SRV_Channels
void update();
// send ESC telemetry messages over MAVLink
void send_esc_telemetry_mavlink(uint8_t mav_chan);
// return true if a particular ESC has been detected
bool is_esc_present(uint8_t chan, uint64_t timeout_ms = 2000);
// test if the Piccolo CAN driver is ready to be armed
bool pre_arm_check(char* reason, uint8_t reason_len);
private:
// loop to send output to ESCs in background thread
void loop();
// write frame on CAN bus, returns true on success
bool write_frame(uavcan::CanFrame &out_frame, uavcan::MonotonicTime timeout);
// read frame on CAN bus, returns true on succses
bool read_frame(uavcan::CanFrame &recv_frame, uavcan::MonotonicTime timeout);
// send ESC commands over CAN
void send_esc_messages(void);
// interpret an ESC message received over CAN
bool handle_esc_message(uavcan::CanFrame &frame);
bool _initialized;
char _thread_name[9];
uint8_t _driver_index;
uavcan::ICanDriver* _can_driver;
const uavcan::CanFrame* _select_frames[uavcan::MaxCanIfaces] { };
HAL_Semaphore _telem_sem;
struct PiccoloESC_Info_t {
// ESC telemetry information
ESC_StatusA_t statusA; //! Telemetry data
ESC_StatusB_t statusB; //! Telemetry data
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];
};

View File

@ -0,0 +1,7 @@
# gitignore file for temporary files generated by Protogen
html/
*.db
*.markdown
*.html

View File

@ -0,0 +1,407 @@
// ESCDefines.c was generated by ProtoGen version 2.18.c
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "ESCDefines.h"
#include "fielddecode.h"
#include "fieldencode.h"
#include "scaleddecode.h"
#include "scaledencode.h"
/*!
* \brief Encode a ESC_StatusBits_t structure into a byte array
*
* The *status* of the ESC is represented using these status bits. ESC system
* functionality can be quickly determined using these bits
* \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_StatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_StatusBits_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_StatusBits_t
/*!
* \brief Decode a ESC_StatusBits_t structure from a byte array
*
* The *status* of the ESC is represented using these status bits. ESC system
* functionality can be quickly determined using these bits
* \param _pg_data points to the byte array to decoded data from
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
* \param _pg_user is the data to decode from the byte array
* \return 1 if the data are decoded, else 0. If 0 is returned _pg_bytecount will not be updated.
*/
int decodeESC_StatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_StatusBits_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_StatusBits_t
/*!
* \brief Encode a ESC_WarningBits_t structure into a byte array
*
* The *warning* bits enumerate various system warnings/errors of which the user
* (or user software) should be made aware. These *warning* bits are transmitted
* in the telemetry packets such that user software is aware of any these
* *warning* conditions and can poll the ESC for particular packets if any
* further information is needed. The ESC will continue to function in the case
* of a *warning* state
* \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_WarningBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_WarningBits_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_WarningBits_t
/*!
* \brief Decode a ESC_WarningBits_t structure from a byte array
*
* The *warning* bits enumerate various system warnings/errors of which the user
* (or user software) should be made aware. These *warning* bits are transmitted
* in the telemetry packets such that user software is aware of any these
* *warning* conditions and can poll the ESC for particular packets if any
* further information is needed. The ESC will continue to function in the case
* of a *warning* state
* \param _pg_data points to the byte array to decoded data from
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
* \param _pg_user is the data to decode from the byte array
* \return 1 if the data are decoded, else 0. If 0 is returned _pg_bytecount will not be updated.
*/
int decodeESC_WarningBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_WarningBits_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_WarningBits_t
/*!
* \brief Encode a ESC_ErrorBits_t structure into a byte array
*
* The *error* bits enumerate critical system errors that will cause the ESC to
* stop functioning until the error cases are alleviated
* \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_ErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_ErrorBits_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_ErrorBits_t
/*!
* \brief Decode a ESC_ErrorBits_t structure from a byte array
*
* The *error* bits enumerate critical system errors that will cause the ESC to
* stop functioning until the error cases are alleviated
* \param _pg_data points to the byte array to decoded data from
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
* \param _pg_user is the data to decode from the byte array
* \return 1 if the data are decoded, else 0. If 0 is returned _pg_bytecount will not be updated.
*/
int decodeESC_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_ErrorBits_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_ErrorBits_t
/*!
* \brief Encode a ESC_TelemetryPackets_t structure into a byte array
*
* These bits are used to determine which packets are automatically transmitted
* as telemetry data by the ESC. Only the packets described here can be
* configured as telemetry packets
* \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_TelemetryPackets_t(uint8_t* _pg_data, int* _pg_bytecount, const ESC_TelemetryPackets_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// If this bit is set, the STATUS_A packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] = (uint8_t)_pg_user->statusA << 7;
// If this bit is set, the STATUS_B packet will be transmitted at the configured rate
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->statusB << 6;
// 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 << 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 << 4;
// 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 << 3;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedB << 2;
// If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->piccoloDownlink << 1;
// Reserved for future use
_pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reservedD;
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
}// encodeESC_TelemetryPackets_t
/*!
* \brief Decode a ESC_TelemetryPackets_t structure from a byte array
*
* These bits are used to determine which packets are automatically transmitted
* as telemetry data by the ESC. Only the packets described here can be
* configured as telemetry packets
* \param _pg_data points to the byte array to decoded data from
* \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded
* \param _pg_user is the data to decode from the byte array
* \return 1 if the data are decoded, else 0. If 0 is returned _pg_bytecount will not be updated.
*/
int decodeESC_TelemetryPackets_t(const uint8_t* _pg_data, int* _pg_bytecount, ESC_TelemetryPackets_t* _pg_user)
{
int _pg_byteindex = *_pg_bytecount;
// If this bit is set, the STATUS_A packet will be transmitted at the configured rate
_pg_user->statusA = (_pg_data[_pg_byteindex] >> 7);
// If this bit is set, the STATUS_B packet will be transmitted at the configured rate
_pg_user->statusB = ((_pg_data[_pg_byteindex] >> 6) & 0x1);
// 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);
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_user->accelerometer = ((_pg_data[_pg_byteindex] >> 4) & 0x1);
// 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);
// Reserved for future use
_pg_user->reservedB = ((_pg_data[_pg_byteindex] >> 2) & 0x1);
// If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
_pg_user->piccoloDownlink = ((_pg_data[_pg_byteindex] >> 1) & 0x1);
// Reserved for future use
_pg_user->reservedD = ((_pg_data[_pg_byteindex]) & 0x1);
_pg_byteindex += 1; // close bit field
*_pg_bytecount = _pg_byteindex;
return 1;
}// decodeESC_TelemetryPackets_t
/*!
* \brief Set a ESC_TelemetryPackets_t structure to initial values.
*
* Set a ESC_TelemetryPackets_t structure to initial values. Not all fields are set,
* only those which the protocol specifies.
* \param _pg_user is the structure whose data are set to initial values
*/
void initESC_TelemetryPackets_t(ESC_TelemetryPackets_t* _pg_user)
{
// If this bit is set, the STATUS_A packet will be transmitted at the configured rate
_pg_user->statusA = 1;
// If this bit is set, the STATUS_B packet will be transmitted at the configured rate
_pg_user->statusB = 1;
// If this bit is set, the STATUS_C packet will be transmitted at the configured rate
_pg_user->statusC = 1;
// If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
_pg_user->accelerometer = 0;
}// initESC_TelemetryPackets_t
// end of ESCDefines.c

View File

@ -0,0 +1,150 @@
// ESCDefines.h was generated by ProtoGen version 2.18.c
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _ESCDEFINES_H
#define _ESCDEFINES_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include "ESCVelocityProtocol.h"
/*!
* The *status* of the ESC is represented using these status bits. ESC system
* functionality can be quickly determined using these bits
*/
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_StatusBits_t;
//! return the minimum encoded length for the ESC_StatusBits_t structure
#define getMinLengthOfESC_StatusBits_t() (1)
//! Encode a ESC_StatusBits_t structure into a byte array
void encodeESC_StatusBits_t(uint8_t* data, int* bytecount, const ESC_StatusBits_t* user);
//! Decode a ESC_StatusBits_t structure from a byte array
int decodeESC_StatusBits_t(const uint8_t* data, int* bytecount, ESC_StatusBits_t* user);
/*!
* The *warning* bits enumerate various system warnings/errors of which the user
* (or user software) should be made aware. These *warning* bits are transmitted
* in the telemetry packets such that user software is aware of any these
* *warning* conditions and can poll the ESC for particular packets if any
* further information is needed. The ESC will continue to function in the case
* of a *warning* state
*/
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_WarningBits_t;
//! return the minimum encoded length for the ESC_WarningBits_t structure
#define getMinLengthOfESC_WarningBits_t() (1)
//! Encode a ESC_WarningBits_t structure into a byte array
void encodeESC_WarningBits_t(uint8_t* data, int* bytecount, const ESC_WarningBits_t* user);
//! Decode a ESC_WarningBits_t structure from a byte array
int decodeESC_WarningBits_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
{
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_ErrorBits_t;
//! return the minimum encoded length for the ESC_ErrorBits_t structure
#define getMinLengthOfESC_ErrorBits_t() (1)
//! Encode a ESC_ErrorBits_t structure into a byte array
void encodeESC_ErrorBits_t(uint8_t* data, int* bytecount, const ESC_ErrorBits_t* user);
//! Decode a ESC_ErrorBits_t structure from a byte array
int decodeESC_ErrorBits_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
* configured as telemetry packets
*/
typedef struct
{
unsigned statusA : 1; //!< If this bit is set, the STATUS_A packet will be transmitted at the configured rate
unsigned statusB : 1; //!< If this bit is set, the STATUS_B packet will be transmitted at the configured rate
unsigned statusC : 1; //!< If this bit is set, the STATUS_C packet will be transmitted at the configured rate
unsigned accelerometer : 1; //!< If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate
unsigned statusD : 1; //!< If this bit is set, the STATUS_D packet will be transmitted at the configured rate
unsigned reservedB : 1; //!< Reserved for future use
unsigned piccoloDownlink : 1; //!< If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)
unsigned reservedD : 1; //!< Reserved for future use
}ESC_TelemetryPackets_t;
// Initial and verify values for TelemetryPackets
#define ESCVelocity_TelemetryPackets_statusA_InitValue 1
#define ESCVelocity_TelemetryPackets_statusB_InitValue 1
#define ESCVelocity_TelemetryPackets_statusC_InitValue 1
#define ESCVelocity_TelemetryPackets_accelerometer_InitValue 0
//! return the minimum encoded length for the ESC_TelemetryPackets_t structure
#define getMinLengthOfESC_TelemetryPackets_t() (1)
//! Encode a ESC_TelemetryPackets_t structure into a byte array
void encodeESC_TelemetryPackets_t(uint8_t* data, int* bytecount, const ESC_TelemetryPackets_t* user);
//! Decode a ESC_TelemetryPackets_t structure from a byte array
int decodeESC_TelemetryPackets_t(const uint8_t* data, int* bytecount, ESC_TelemetryPackets_t* user);
//! Set a ESC_TelemetryPackets_t structure to initial values
void initESC_TelemetryPackets_t(ESC_TelemetryPackets_t* user);
#ifdef __cplusplus
}
#endif
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,458 @@
// ESCPackets.h was generated by ProtoGen version 2.18.c
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _ESCPACKETS_H
#define _ESCPACKETS_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include "ESCVelocityProtocol.h"
#include "ESCDefines.h"
/*!
* Telemetry settings (storage class)
*/
typedef struct
{
uint8_t period; //!< Telemetry period
uint8_t silence; //!< Telemetry silence period (delay after RESET before telemetry data is sent)
ESC_TelemetryPackets_t packets; //!< Bitfield describing which telemetry packets are enabled
}ESC_TelemetryConfig_t;
// Initial and verify values for TelemetryConfig
#define ESCVelocity_TelemetryConfig_period_InitValue 4
#define ESCVelocity_TelemetryConfig_period_VerifyMax 250
#define ESCVelocity_TelemetryConfig_silence_InitValue 20
#define ESCVelocity_TelemetryConfig_silence_VerifyMax 250
//! Encode a ESC_TelemetryConfig_t structure into a byte array
void encodeESC_TelemetryConfig_t(uint8_t* data, int* bytecount, const ESC_TelemetryConfig_t* user);
//! Decode a ESC_TelemetryConfig_t structure from a byte array
int decodeESC_TelemetryConfig_t(const uint8_t* data, int* bytecount, ESC_TelemetryConfig_t* user);
//! Set a ESC_TelemetryConfig_t structure to initial values
void initESC_TelemetryConfig_t(ESC_TelemetryConfig_t* user);
//! Verify a ESC_TelemetryConfig_t structure has acceptable values
int verifyESC_TelemetryConfig_t(ESC_TelemetryConfig_t* user);
//! Create the ESC_TelemetryConfig packet
void encodeESC_TelemetryConfigPacketStructure(void* pkt, const ESC_TelemetryConfig_t* user);
//! Decode the ESC_TelemetryConfig packet
int decodeESC_TelemetryConfigPacketStructure(const void* pkt, ESC_TelemetryConfig_t* user);
//! Create the ESC_TelemetryConfig packet
void encodeESC_TelemetryConfigPacket(void* pkt, uint8_t period, uint8_t silence, const ESC_TelemetryPackets_t* packets);
//! Decode the ESC_TelemetryConfig packet
int decodeESC_TelemetryConfigPacket(const void* pkt, uint8_t* period, uint8_t* silence, ESC_TelemetryPackets_t* packets);
//! return the packet ID for the ESC_TelemetryConfig packet
#define getESC_TelemetryConfigPacketID() (PKT_ESC_TELEMETRY_SETTINGS)
//! return the minimum encoded length for the ESC_TelemetryConfig packet
#define getESC_TelemetryConfigMinDataLength() (3)
//! return the maximum encoded length for the ESC_TelemetryConfig packet
#define getESC_TelemetryConfigMaxDataLength() (3)
/*!
* Send this packet to command ESCs which have CAN ID values in the range {1,4}
* (inclusive). This packet must be sent as a broadcast packet (address = 0xFF)
* such that all ESCs can receive it. Similiar commands are available for
* commanding ESCs with ID values up to 64, using different ESC_SETPOINT_x
* packet ID values.
*/
typedef struct
{
uint16_t pwmValueA; //!< The PWM (pulse width) command for ESC with CAN ID 1
uint16_t pwmValueB; //!< The PWM (pulse width) command for ESC with CAN ID 2
uint16_t pwmValueC; //!< The PWM (pulse width) command for ESC with CAN ID 3
uint16_t pwmValueD; //!< The PWM (pulse width) command for ESC with CAN ID 4
}ESC_CommandMultipleESCs_t;
//! Create the ESC_CommandMultipleESCs packet
void encodeESC_CommandMultipleESCsPacket(void* pkt, uint16_t pwmValueA, uint16_t pwmValueB, uint16_t pwmValueC, uint16_t pwmValueD, uint32_t id);
//! Decode the ESC_CommandMultipleESCs packet
int decodeESC_CommandMultipleESCsPacket(const void* pkt, uint16_t* pwmValueA, uint16_t* pwmValueB, uint16_t* pwmValueC, uint16_t* pwmValueD);
//! return the minimum encoded length for the ESC_CommandMultipleESCs packet
#define getESC_CommandMultipleESCsMinDataLength() (8)
//! return the maximum encoded length for the ESC_CommandMultipleESCs packet
#define getESC_CommandMultipleESCsMaxDataLength() (8)
//! Create the ESC_Disable packet
void encodeESC_DisablePacket(void* pkt);
//! Decode the ESC_Disable packet
int decodeESC_DisablePacket(const void* pkt);
//! return the packet ID for the ESC_Disable packet
#define getESC_DisablePacketID() (PKT_ESC_DISABLE)
//! return the minimum encoded length for the ESC_Disable packet
#define getESC_DisableMinDataLength() (2)
//! return the maximum encoded length for the ESC_Disable packet
#define getESC_DisableMaxDataLength() (2)
//! Create the ESC_Enable packet
void encodeESC_EnablePacket(void* pkt);
//! Decode the ESC_Enable packet
int decodeESC_EnablePacket(const void* pkt);
//! return the packet ID for the ESC_Enable packet
#define getESC_EnablePacketID() (PKT_ESC_STANDBY)
//! return the minimum encoded length for the ESC_Enable packet
#define getESC_EnableMinDataLength() (2)
//! return the maximum encoded length for the ESC_Enable packet
#define getESC_EnableMaxDataLength() (2)
//! Create the ESC_PWMCommand packet
void encodeESC_PWMCommandPacket(void* pkt, uint16_t pwmCommand);
//! Decode the ESC_PWMCommand packet
int decodeESC_PWMCommandPacket(const void* pkt, uint16_t* pwmCommand);
//! return the packet ID for the ESC_PWMCommand packet
#define getESC_PWMCommandPacketID() (PKT_ESC_PWM_CMD)
//! return the minimum encoded length for the ESC_PWMCommand packet
#define getESC_PWMCommandMinDataLength() (2)
//! return the maximum encoded length for the ESC_PWMCommand packet
#define getESC_PWMCommandMaxDataLength() (2)
//! Create the ESC_RPMCommand packet
void encodeESC_RPMCommandPacket(void* pkt, uint16_t rpmCommand);
//! Decode the ESC_RPMCommand packet
int decodeESC_RPMCommandPacket(const void* pkt, uint16_t* rpmCommand);
//! return the packet ID for the ESC_RPMCommand packet
#define getESC_RPMCommandPacketID() (PKT_ESC_RPM_CMD)
//! return the minimum encoded length for the ESC_RPMCommand packet
#define getESC_RPMCommandMinDataLength() (2)
//! return the maximum encoded length for the ESC_RPMCommand packet
#define getESC_RPMCommandMaxDataLength() (2)
/*!
* The ESC_STATUS_A packet contains high-priority ESC status information. This
* packet is transmitted by the ESC at regular (user-configurable) intervals. It
* can also be requested (polled) from the ESC by sending a zero-length packet
* of the same type.
*/
typedef struct
{
uint8_t mode; //!< ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use.
ESC_StatusBits_t status; //!< ESC status bits
ESC_WarningBits_t warnings; //!< ESC warning bits
ESC_ErrorBits_t errors; //!< ESC *error* bits
uint16_t command; //!< ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM
uint16_t rpm; //!< Motor speed
}ESC_StatusA_t;
//! Create the ESC_StatusA packet
void encodeESC_StatusAPacketStructure(void* pkt, const ESC_StatusA_t* user);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacketStructure(const void* pkt, ESC_StatusA_t* user);
//! Create the ESC_StatusA packet
void encodeESC_StatusAPacket(void* pkt, uint8_t mode, const ESC_StatusBits_t* status, const ESC_WarningBits_t* warnings, const ESC_ErrorBits_t* errors, uint16_t command, uint16_t rpm);
//! Decode the ESC_StatusA packet
int decodeESC_StatusAPacket(const void* pkt, uint8_t* mode, ESC_StatusBits_t* status, ESC_WarningBits_t* warnings, ESC_ErrorBits_t* errors, uint16_t* command, uint16_t* rpm);
//! return the packet ID for the ESC_StatusA packet
#define getESC_StatusAPacketID() (PKT_ESC_STATUS_A)
//! return the minimum encoded length for the ESC_StatusA packet
#define getESC_StatusAMinDataLength() (8)
//! return the maximum encoded length for the ESC_StatusA packet
#define getESC_StatusAMaxDataLength() (8)
/*!
* The ESC_STATUS_B packet contains ESC operational information. This packet is
* transmitted by the ESC at regular (user-configurable) intervals. It can also
* be requested (polled) from the ESC by sending a zero-length packet of the
* same type.
*/
typedef struct
{
uint16_t voltage; //!< ESC Rail Voltage
int16_t current; //!< ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative
uint16_t dutyCycle; //!< ESC Motor Duty Cycle
int8_t escTemperature; //!< ESC Board Temperature
uint8_t motorTemperature; //!< ESC Motor Temperature
}ESC_StatusB_t;
//! Create the ESC_StatusB packet
void encodeESC_StatusBPacketStructure(void* pkt, const ESC_StatusB_t* user);
//! Decode the ESC_StatusB packet
int decodeESC_StatusBPacketStructure(const void* pkt, ESC_StatusB_t* user);
//! Create the ESC_StatusB packet
void encodeESC_StatusBPacket(void* pkt, uint16_t voltage, int16_t current, uint16_t dutyCycle, int8_t escTemperature, uint8_t motorTemperature);
//! Decode the ESC_StatusB packet
int decodeESC_StatusBPacket(const void* pkt, uint16_t* voltage, int16_t* current, uint16_t* dutyCycle, int8_t* escTemperature, uint8_t* motorTemperature);
//! return the packet ID for the ESC_StatusB packet
#define getESC_StatusBPacketID() (PKT_ESC_STATUS_B)
//! return the minimum encoded length for the ESC_StatusB packet
#define getESC_StatusBMinDataLength() (8)
//! return the maximum encoded length for the ESC_StatusB packet
#define getESC_StatusBMaxDataLength() (8)
/*!
* This packet contains raw accelerometer data from the ESC. It can be requested
* (polled) from the ESC by sending a zero-length packet of the same type. It
* can also be transmitted by the ESC at high-frequency using the high-frequency
* streaming functionality of the ESC
*/
typedef struct
{
int16_t xAcc; //!< X axis acceleration value
int16_t yAcc; //!< Y axis acceleration value
int16_t zAcc; //!< Z axis acceleration value
uint8_t fullscale; //!< Accelerometer full-scale range
uint8_t resolution; //!< Accelerometer measurement resolution, in 'bits'.
}ESC_Accelerometer_t;
//! Create the ESC_Accelerometer packet
void encodeESC_AccelerometerPacketStructure(void* pkt, const ESC_Accelerometer_t* user);
//! Decode the ESC_Accelerometer packet
int decodeESC_AccelerometerPacketStructure(const void* pkt, ESC_Accelerometer_t* user);
//! Create the ESC_Accelerometer packet
void encodeESC_AccelerometerPacket(void* pkt, int16_t xAcc, int16_t yAcc, int16_t zAcc, uint8_t fullscale, uint8_t resolution);
//! Decode the ESC_Accelerometer packet
int decodeESC_AccelerometerPacket(const void* pkt, int16_t* xAcc, int16_t* yAcc, int16_t* zAcc, uint8_t* fullscale, uint8_t* resolution);
//! return the packet ID for the ESC_Accelerometer packet
#define getESC_AccelerometerPacketID() (PKT_ESC_ACCELEROMETER)
//! return the minimum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMinDataLength() (8)
//! return the maximum encoded length for the ESC_Accelerometer packet
#define getESC_AccelerometerMaxDataLength() (8)
/*!
* This packet contains the serial number for the ESC. Additionally there are
* two extra values (each 16-bit) which can be programmed by the user for any
* purpose.
*/
typedef struct
{
uint8_t HardwareRevision; //!< ESC hardware revision
uint32_t SerialNumber; //!< ESC Serial Number (OTP - not configurable by user)
uint16_t UserIDA; //!< User ID Value A - user can set this value to any value
uint16_t UserIDB; //!< User ID Value B - user can set this value to any value
}ESC_Address_t;
//! Create the ESC_Address packet
void encodeESC_AddressPacketStructure(void* pkt, const ESC_Address_t* user);
//! Decode the ESC_Address packet
int decodeESC_AddressPacketStructure(const void* pkt, ESC_Address_t* user);
//! Create the ESC_Address packet
void encodeESC_AddressPacket(void* pkt, uint8_t HardwareRevision, uint32_t SerialNumber, uint16_t UserIDA, uint16_t UserIDB);
//! Decode the ESC_Address packet
int decodeESC_AddressPacket(const void* pkt, uint8_t* HardwareRevision, uint32_t* SerialNumber, uint16_t* UserIDA, uint16_t* UserIDB);
//! return the packet ID for the ESC_Address packet
#define getESC_AddressPacketID() (PKT_ESC_SERIAL_NUMBER)
//! return the minimum encoded length for the ESC_Address packet
#define getESC_AddressMinDataLength() (8)
//! return the maximum encoded length for the ESC_Address packet
#define getESC_AddressMaxDataLength() (8)
//! Create the ESC_Title packet
void encodeESC_TitlePacket(void* pkt, const uint8_t ESCTitle[8]);
//! Decode the ESC_Title packet
int decodeESC_TitlePacket(const void* pkt, uint8_t ESCTitle[8]);
//! return the packet ID for the ESC_Title packet
#define getESC_TitlePacketID() (PKT_ESC_TITLE)
//! return the minimum encoded length for the ESC_Title packet
#define getESC_TitleMinDataLength() (8)
//! return the maximum encoded length for the ESC_Title packet
#define getESC_TitleMaxDataLength() (8)
/*!
* This packet contains the firmware version of the ESC
*/
typedef struct
{
uint8_t versionMajor; //!< Major firmware version number
uint8_t versionMinor; //!< Minor firmware version numner
uint8_t versionDay; //!< Firmware release date, day-of-month
uint8_t versionMonth; //!< Firmware release data, month-of-year
uint16_t versionYear; //!< Firmware release date, year
uint16_t firmwareChecksum; //!< Firmware checksum
}ESC_Firmware_t;
//! Create the ESC_Firmware packet
void encodeESC_FirmwarePacketStructure(void* pkt, const ESC_Firmware_t* user);
//! Decode the ESC_Firmware packet
int decodeESC_FirmwarePacketStructure(const void* pkt, ESC_Firmware_t* user);
//! Create the ESC_Firmware packet
void encodeESC_FirmwarePacket(void* pkt, uint8_t versionMajor, uint8_t versionMinor, uint8_t versionDay, uint8_t versionMonth, uint16_t versionYear, uint16_t firmwareChecksum);
//! Decode the ESC_Firmware packet
int decodeESC_FirmwarePacket(const void* pkt, uint8_t* versionMajor, uint8_t* versionMinor, uint8_t* versionDay, uint8_t* versionMonth, uint16_t* versionYear, uint16_t* firmwareChecksum);
//! return the packet ID for the ESC_Firmware packet
#define getESC_FirmwarePacketID() (PKT_ESC_FIRMWARE)
//! return the minimum encoded length for the ESC_Firmware packet
#define getESC_FirmwareMinDataLength() (8)
//! return the maximum encoded length for the ESC_Firmware packet
#define getESC_FirmwareMaxDataLength() (8)
/*!
* This packet contains system runtime information
*/
typedef struct
{
uint32_t millisecondsSinceReset; //!< Number of milliseconds since the ESC last experienced a reset/power-on event
uint16_t powerCycles; //!< Number of power cycle events that the ESC has experienced
uint8_t resetCode; //!< Processor RESET code for debug purposes
uint8_t cpuOccupancy; //!< Processor usage
}ESC_SystemInfo_t;
//! Create the ESC_SystemInfo packet
void encodeESC_SystemInfoPacketStructure(void* pkt, const ESC_SystemInfo_t* user);
//! Decode the ESC_SystemInfo packet
int decodeESC_SystemInfoPacketStructure(const void* pkt, ESC_SystemInfo_t* user);
//! Create the ESC_SystemInfo packet
void encodeESC_SystemInfoPacket(void* pkt, uint32_t millisecondsSinceReset, uint16_t powerCycles, uint8_t resetCode, uint8_t cpuOccupancy);
//! Decode the ESC_SystemInfo packet
int decodeESC_SystemInfoPacket(const void* pkt, uint32_t* millisecondsSinceReset, uint16_t* powerCycles, uint8_t* resetCode, uint8_t* cpuOccupancy);
//! return the packet ID for the ESC_SystemInfo packet
#define getESC_SystemInfoPacketID() (PKT_ESC_SYSTEM_INFO)
//! return the minimum encoded length for the ESC_SystemInfo packet
#define getESC_SystemInfoMinDataLength() (8)
//! return the maximum encoded length for the ESC_SystemInfo packet
#define getESC_SystemInfoMaxDataLength() (8)
/*!
* This packet contains the telemetry packet configuration
*/
typedef struct
{
ESC_TelemetryConfig_t settings; //!< Telemetry settings
char apiVersion[5]; //!< The API version of the ESC. Field is encoded constant.
}ESC_TelemetrySettings_t;
//! Set a ESC_TelemetrySettings_t structure to initial values
void initESC_TelemetrySettings_t(ESC_TelemetrySettings_t* user);
//! Verify a ESC_TelemetrySettings_t structure has acceptable values
int verifyESC_TelemetrySettings_t(ESC_TelemetrySettings_t* user);
//! Create the ESC_TelemetrySettings packet
void encodeESC_TelemetrySettingsPacket(void* pkt, const ESC_TelemetryConfig_t* settings);
//! Decode the ESC_TelemetrySettings packet
int decodeESC_TelemetrySettingsPacket(const void* pkt, ESC_TelemetryConfig_t* settings, char apiVersion[5]);
//! return the packet ID for the ESC_TelemetrySettings packet
#define getESC_TelemetrySettingsPacketID() (PKT_ESC_TELEMETRY_SETTINGS)
//! return the minimum encoded length for the ESC_TelemetrySettings packet
#define getESC_TelemetrySettingsMinDataLength() (4)
//! return the maximum encoded length for the ESC_TelemetrySettings packet
#define getESC_TelemetrySettingsMaxDataLength() (8)
/*!
* This packet contains information on the non-volatile ESC settings
*/
typedef struct
{
uint8_t version; //!< Version of EEPROM data
uint16_t size; //!< Size of settings data
uint16_t checksum; //!< Settings checksum
}ESC_EEPROMSettings_t;
//! Create the ESC_EEPROMSettings packet
void encodeESC_EEPROMSettingsPacketStructure(void* pkt, const ESC_EEPROMSettings_t* user);
//! Decode the ESC_EEPROMSettings packet
int decodeESC_EEPROMSettingsPacketStructure(const void* pkt, ESC_EEPROMSettings_t* user);
//! Create the ESC_EEPROMSettings packet
void encodeESC_EEPROMSettingsPacket(void* pkt, uint8_t version, uint16_t size, uint16_t checksum);
//! Decode the ESC_EEPROMSettings packet
int decodeESC_EEPROMSettingsPacket(const void* pkt, uint8_t* version, uint16_t* size, uint16_t* checksum);
//! return the packet ID for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsPacketID() (PKT_ESC_EEPROM)
//! return the minimum encoded length for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsMinDataLength() (5)
//! return the maximum encoded length for the ESC_EEPROMSettings packet
#define getESC_EEPROMSettingsMaxDataLength() (5)
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,232 @@
// ESCVelocityProtocol.c was generated by ProtoGen version 2.18.c
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "ESCVelocityProtocol.h"
/*!
* \brief Lookup label for 'ESCOperatingModes' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCOperatingModes_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_MODE_STANDBY:
return "ESC_MODE_STANDBY";
case ESC_MODE_PWM:
return "ESC_MODE_PWM";
case ESC_MODE_RPM:
return "ESC_MODE_RPM";
case ESC_VALID_MODES:
return "ESC_VALID_MODES";
}
}
/*!
* \brief Lookup label for 'ESCCommandSources' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCCommandSources_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_COMMAND_SOURCE_NONE:
return "ESC_COMMAND_SOURCE_NONE";
case ESC_COMMAND_SOURCE_CAN:
return "ESC_COMMAND_SOURCE_CAN";
case ESC_COMMAND_SOURCE_PWM:
return "ESC_COMMAND_SOURCE_PWM";
}
}
/*!
* \brief Lookup label for 'ESCMotorTemperatureSensor' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCMotorTemperatureSensor_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case ESC_MOTOR_TEMP_SENSOR_OFF:
return "ESC_MOTOR_TEMP_SENSOR_OFF";
case ESC_MOTOR_TEMP_SENSOR_KTY84:
return "ESC_MOTOR_TEMP_SENSOR_KTY84";
case ESC_MOTOR_TEMP_SENSOR_KTY83:
return "ESC_MOTOR_TEMP_SENSOR_KTY83";
}
}
/*!
* \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 "ESC_COMMAND_PRIORITY_CAN_ONLY";
case ESC_COMMAND_PRIORITY_CAN_PRIORITY:
return "ESC_COMMAND_PRIORITY_CAN_PRIORITY";
case ESC_COMMAND_PRIORITY_PWM_PRIORITY:
return "ESC_COMMAND_PRIORITY_PWM_PRIORITY";
}
}
/*!
* \brief Lookup label for 'ESCMultiCommandPackets' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCMultiCommandPackets_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case PKT_ESC_SETPOINT_1:
return "PKT_ESC_SETPOINT_1";
case PKT_ESC_SETPOINT_2:
return "PKT_ESC_SETPOINT_2";
case PKT_ESC_SETPOINT_3:
return "PKT_ESC_SETPOINT_3";
case PKT_ESC_SETPOINT_4:
return "PKT_ESC_SETPOINT_4";
case PKT_ESC_SETPOINT_5:
return "PKT_ESC_SETPOINT_5";
case PKT_ESC_SETPOINT_6:
return "PKT_ESC_SETPOINT_6";
case PKT_ESC_SETPOINT_7:
return "PKT_ESC_SETPOINT_7";
case PKT_ESC_SETPOINT_8:
return "PKT_ESC_SETPOINT_8";
case PKT_ESC_SETPOINT_9:
return "PKT_ESC_SETPOINT_9";
case PKT_ESC_SETPOINT_10:
return "PKT_ESC_SETPOINT_10";
case PKT_ESC_SETPOINT_11:
return "PKT_ESC_SETPOINT_11";
case PKT_ESC_SETPOINT_12:
return "PKT_ESC_SETPOINT_12";
case PKT_ESC_SETPOINT_13:
return "PKT_ESC_SETPOINT_13";
case PKT_ESC_SETPOINT_14:
return "PKT_ESC_SETPOINT_14";
case PKT_ESC_SETPOINT_15:
return "PKT_ESC_SETPOINT_15";
case PKT_ESC_SETPOINT_16:
return "PKT_ESC_SETPOINT_16";
}
}
/*!
* \brief Lookup label for 'ESCCommandPackets' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCCommandPackets_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case PKT_ESC_PWM_CMD:
return "PKT_ESC_PWM_CMD";
case PKT_ESC_RPM_CMD:
return "PKT_ESC_RPM_CMD";
case PKT_ESC_DISABLE:
return "PKT_ESC_DISABLE";
case PKT_ESC_STANDBY:
return "PKT_ESC_STANDBY";
}
}
/*!
* \brief Lookup label for 'ESCStatusPackets' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCStatusPackets_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case PKT_ESC_STATUS_A:
return "PKT_ESC_STATUS_A";
case PKT_ESC_STATUS_B:
return "PKT_ESC_STATUS_B";
case PKT_ESC_ACCELEROMETER:
return "PKT_ESC_ACCELEROMETER";
}
}
/*!
* \brief Lookup label for 'ESCPackets' enum entry
*
* \param value is the integer value of the enum entry
* \return string label of the given entry
*/
const char* ESCPackets_EnumLabel(int value)
{
switch (value)
{
default:
return "";
case PKT_ESC_SERIAL_NUMBER:
return "PKT_ESC_SERIAL_NUMBER";
case PKT_ESC_TITLE:
return "PKT_ESC_TITLE";
case PKT_ESC_FIRMWARE:
return "PKT_ESC_FIRMWARE";
case PKT_ESC_SYSTEM_INFO:
return "PKT_ESC_SYSTEM_INFO";
case PKT_ESC_TELEMETRY_SETTINGS:
return "PKT_ESC_TELEMETRY_SETTINGS";
case PKT_ESC_EEPROM:
return "PKT_ESC_EEPROM";
}
}
// end of ESCVelocityProtocol.c

View File

@ -0,0 +1,233 @@
// ESCVelocityProtocol.h was generated by ProtoGen version 2.18.c
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _ESCVELOCITYPROTOCOL_H
#define _ESCVELOCITYPROTOCOL_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
* \mainpage ESCVelocity protocol stack
*
* This is the ICD for the Currawong Engineering Electronic Speed Controller
* (ESCVelocity). This document details the ESCVelocity command and packet
* structure for communication with and configuration of the ESC
*
* 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: 23
*
* The protocol version is 3.05
*/
#include <stdint.h>
#include <string.h> // C string manipulation function header
//! \return the protocol API enumeration
#define getESCVelocityApi() 23
//! \return the protocol version string
#define getESCVelocityVersion() "3.05"
/*!
* ESC_Disable_Sequence
*/
typedef enum
{
ESC_DISABLE_A = 0xAA,//!< Constant value required for disabling the ESC
ESC_DISABLE_B = 0xC3 //!< Constant value required for disabling the ESC
} ESCDisableSequence;
/*!
* ESC_Enable_Sequence
*/
typedef enum
{
ESC_ENABLE_A = 0xAA, //!< Constant value required for enabling the ESC
ESC_ENABLE_B = 0x3C //!< Constant value required for enabling the ESC
} ESCEnableSequence;
/*!
* ESC Operational Modes
*/
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_VALID_MODES //!< ESC mode counter
} ESCOperatingModes;
//! \return the label of a 'ESCOperatingModes' enum entry, based on its value
const char* ESCOperatingModes_EnumLabel(int value);
/*!
* ESC Command Sources
*/
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
} ESCCommandSources;
//! \return the label of a 'ESCCommandSources' enum entry, based on its value
const char* ESCCommandSources_EnumLabel(int value);
/*!
* ESC motor temperature sensor options
*/
typedef enum
{
ESC_MOTOR_TEMP_SENSOR_OFF = 0x00,//!< No temperature sensor selected
ESC_MOTOR_TEMP_SENSOR_KTY84, //!< KTY84 of equivalent
ESC_MOTOR_TEMP_SENSOR_KTY83 //!< KTY83 or equivalent
} 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 Enumeration
*/
typedef enum
{
ESC_MOTOR_DIR_FORWARD = 0x00,//!< Forward motor direction
ESC_MOTOR_DIR_REVERSE = 0x01 //!< Reverse motor direction
} ESCMotorDirections;
/*!
* Motor beep modes enumeration
*/
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
} ESCBeepModes;
/*!
* ESC Multi Command Packets
*/
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
} ESCMultiCommandPackets;
//! \return the label of a 'ESCMultiCommandPackets' enum entry, based on its value
const char* ESCMultiCommandPackets_EnumLabel(int value);
/*!
* ESC Command Packets
*/
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
} ESCCommandPackets;
//! \return the label of a 'ESCCommandPackets' enum entry, based on its value
const char* ESCCommandPackets_EnumLabel(int value);
/*!
* ESC Status Packets
*/
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_ACCELEROMETER = 0x88 //!< Raw accelerometer data
} ESCStatusPackets;
//! \return the label of a 'ESCStatusPackets' enum entry, based on its value
const char* ESCStatusPackets_EnumLabel(int value);
/*!
* ESC Packets Definitions
*/
typedef enum
{
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
} ESCPackets;
//! \return the label of a 'ESCPackets' enum entry, based on its value
const char* ESCPackets_EnumLabel(int value);
// The prototypes below provide an interface to the packets.
// They are not auto-generated functions, but must be hand-written
//! \return the packet data pointer from the packet
uint8_t* getESCVelocityPacketData(void* pkt);
//! \return the packet data pointer from the packet, const
const uint8_t* getESCVelocityPacketDataConst(const void* pkt);
//! Complete a packet after the data have been encoded
void finishESCVelocityPacket(void* pkt, int size, uint32_t packetID);
//! \return the size of a packet from the packet header
int getESCVelocityPacketSize(const void* pkt);
//! \return the ID of a packet from the packet header
uint32_t getESCVelocityPacketID(const void* pkt);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,9 @@
# Piccolo Protocol Generation
The Piccolo CAN protocol messages are generated using the [ProtoGen](https://github.com/billvaglienti/ProtoGen) protocol generation tool.
The raw protocol definition for each device type is provided in a `.xml` file (e.g. `protocol_esc_velocity.xml`).
To regenerate the protocol, run the following command:
`protogen.exe protocol_esc_velocity.xml --license license.txt`

View File

@ -0,0 +1,434 @@
// fielddecode.c was generated by ProtoGen version 2.18.c
#include "fielddecode.h"
/*!
* Decode a null terminated string from a byte stream
* \param string receives the deocded null-terminated string.
* \param bytes is a pointer to the byte stream to be decoded.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by the number of bytes decoded when this function
* is complete.
* \param maxLength is the maximum number of bytes that can be decoded.
* maxLength includes the null terminator, which is always applied.
* \param fixedLength should be 1 to force the number of bytes decoded to be
* exactly equal to maxLength.
*/
void stringFromBytes(char* string, const uint8_t* bytes, int* index, int maxLength, int fixedLength)
{
int i;
// increment byte pointer for starting point
bytes += *index;
for(i = 0; i < maxLength - 1; i++)
{
if(bytes[i] == 0)
break;
else
string[i] = (char)bytes[i];
}
// Make sure we include null terminator
string[i++] = 0;
if(fixedLength)
(*index) += maxLength;
else
(*index) += i;
}// stringFromBytes
/*!
* Copy an array of bytes from a byte stream without changing the order.
* \param data receives the copied bytes
* \param bytes is a pointer to the byte stream to be copied from.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by num when this function is complete.
* \param num is the number of bytes to copy
*/
void bytesFromBeBytes(uint8_t* data, const uint8_t* bytes, int* index, int num)
{
// increment byte pointer for starting point
bytes += (*index);
// Increment byte index to indicate number of bytes copied
(*index) += num;
// Copy the bytes without changing the order
while(num > 0)
{
*(data++) = *(bytes++);
num--;
}
}// bytesFromBeBytes
/*!
* Copy an array of bytes from a byte stream, reversing the order.
* \param data receives the copied bytes
* \param bytes is a pointer to the byte stream to be copied.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by num when this function is complete.
* \param num is the number of bytes to copy
*/
void bytesFromLeBytes(uint8_t* data, const uint8_t* bytes, int* index, int num)
{
// increment byte pointer for starting point
bytes += (*index);
// Increment byte index to indicate number of bytes copied
(*index) += num;
// To encode as "little endian bytes", (a nonsensical statement), reverse the byte order
bytes += (num - 1);
// Copy the bytes, reversing the order
while(num > 0)
{
*(data++) = *(bytes--);
num--;
}
}// bytesFromLeBytes
/*!
* Decode a 4 byte float from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \return the number decoded from the byte stream
*/
float float32FromBeBytes(const uint8_t* bytes, int* index)
{
union
{
float floatValue;
uint32_t integerValue;
}field;
field.integerValue = uint32FromBeBytes(bytes, index);
return field.floatValue;
}
/*!
* Decode a 4 byte float from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \return the number decoded from the byte stream
*/
float float32FromLeBytes(const uint8_t* bytes, int* index)
{
union
{
float floatValue;
uint32_t integerValue;
}field;
field.integerValue = uint32FromLeBytes(bytes, index);
return field.floatValue;
}
/*!
* Decode a unsigned 4 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \return the number decoded from the byte stream
*/
uint32_t uint32FromBeBytes(const uint8_t* bytes, int* index)
{
uint32_t number;
// increment byte pointer for starting point
bytes += *index;
number = *(bytes++);
number = (number << 8) | *(bytes++);
number = (number << 8) | *(bytes++);
number = (number << 8) | *bytes;
(*index) += 4;
return number;
}
/*!
* Decode a unsigned 4 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \return the number decoded from the byte stream
*/
uint32_t uint32FromLeBytes(const uint8_t* bytes, int* index)
{
uint32_t number;
// increment byte pointer for starting point
bytes += (*index) + 3;
number = *(bytes--);
number = (number << 8) | *(bytes--);
number = (number << 8) | *(bytes--);
number = (number << 8) | *bytes;
(*index) += 4;
return number;
}
/*!
* Decode a signed 4 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \return the number decoded from the byte stream
*/
int32_t int32FromBeBytes(const uint8_t* bytes, int* index)
{
int32_t number;
// increment byte pointer for starting point
bytes += *index;
number = *(bytes++);
number = (number << 8) | *(bytes++);
number = (number << 8) | *(bytes++);
number = (number << 8) | *bytes;
(*index) += 4;
return number;
}
/*!
* Decode a signed 4 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \return the number decoded from the byte stream
*/
int32_t int32FromLeBytes(const uint8_t* bytes, int* index)
{
int32_t number;
// increment byte pointer for starting point
bytes += (*index) + 3;
number = *(bytes--);
number = (number << 8) | *(bytes--);
number = (number << 8) | *(bytes--);
number = (number << 8) | *bytes;
(*index) += 4;
return number;
}
/*!
* Decode a unsigned 3 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \return the number decoded from the byte stream
*/
uint32_t uint24FromBeBytes(const uint8_t* bytes, int* index)
{
uint32_t number;
// increment byte pointer for starting point
bytes += *index;
number = *(bytes++);
number = (number << 8) | *(bytes++);
number = (number << 8) | *bytes;
(*index) += 3;
return number;
}
/*!
* Decode a unsigned 3 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \return the number decoded from the byte stream
*/
uint32_t uint24FromLeBytes(const uint8_t* bytes, int* index)
{
uint32_t number;
// increment byte pointer for starting point
bytes += (*index) + 2;
number = *(bytes--);
number = (number << 8) | *(bytes--);
number = (number << 8) | *bytes;
(*index) += 3;
return number;
}
/*!
* Decode a signed 3 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \return the number decoded from the byte stream
*/
int32_t int24FromBeBytes(const uint8_t* bytes, int* index)
{
// Signed value in non-native size, requires sign extension. Algorithm
// courtesty of: https://graphics.stanford.edu/~seander/bithacks.html
const int32_t m = 0x00800000;
int32_t number;
// increment byte pointer for starting point
bytes += *index;
number = *(bytes++);
number = (number << 8) | *(bytes++);
number = (number << 8) | *bytes;
(*index) += 3;
return (number ^ m) - m;
}
/*!
* Decode a signed 3 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \return the number decoded from the byte stream
*/
int32_t int24FromLeBytes(const uint8_t* bytes, int* index)
{
// Signed value in non-native size, requires sign extension. Algorithm
// courtesty of: https://graphics.stanford.edu/~seander/bithacks.html
const int32_t m = 0x00800000;
int32_t number;
// increment byte pointer for starting point
bytes += (*index) + 2;
number = *(bytes--);
number = (number << 8) | *(bytes--);
number = (number << 8) | *bytes;
(*index) += 3;
return (number ^ m) - m;
}
/*!
* Decode a unsigned 2 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \return the number decoded from the byte stream
*/
uint16_t uint16FromBeBytes(const uint8_t* bytes, int* index)
{
uint16_t number;
// increment byte pointer for starting point
bytes += *index;
number = *(bytes++);
number = (number << 8) | *bytes;
(*index) += 2;
return number;
}
/*!
* Decode a unsigned 2 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \return the number decoded from the byte stream
*/
uint16_t uint16FromLeBytes(const uint8_t* bytes, int* index)
{
uint16_t number;
// increment byte pointer for starting point
bytes += (*index) + 1;
number = *(bytes--);
number = (number << 8) | *bytes;
(*index) += 2;
return number;
}
/*!
* Decode a signed 2 byte integer from a big endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \return the number decoded from the byte stream
*/
int16_t int16FromBeBytes(const uint8_t* bytes, int* index)
{
int16_t number;
// increment byte pointer for starting point
bytes += *index;
number = *(bytes++);
number = (number << 8) | *bytes;
(*index) += 2;
return number;
}
/*!
* Decode a signed 2 byte integer from a little endian byte stream.
* \param bytes is a pointer to the byte stream which contains the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \return the number decoded from the byte stream
*/
int16_t int16FromLeBytes(const uint8_t* bytes, int* index)
{
int16_t number;
// increment byte pointer for starting point
bytes += (*index) + 1;
number = *(bytes--);
number = (number << 8) | *bytes;
(*index) += 2;
return number;
}
// end of fielddecode.c

View File

@ -0,0 +1,110 @@
// fielddecode.h was generated by ProtoGen version 2.18.c
#ifndef _FIELDDECODE_H
#define _FIELDDECODE_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
* fielddecode provides routines to pull numbers from a byte stream.
*
* fielddecode provides routines to pull numbers in local memory layout from
* a big or little endian byte stream. It is the opposite operation from the
* routines contained in fieldencode.h
*
* When compressing unsigned numbers (for example 32-bits to 16-bits) the most
* signficant bytes are discarded and the only requirement is that the value of
* the number fits in the smaller width. When going the other direction the
* most significant bytes are simply set to 0x00. However signed two's
* complement numbers are more complicated.
*
* If the signed value is a positive number that fits in the range then the
* most significant byte will be zero, and we can discard it. If the signed
* value is negative (in two's complement) then the most significant bytes are
* 0xFF and again we can throw them away. See the example below
*
* 32-bit +100 | 16-bit +100 | 8-bit +100
* 0x00000064 | 0x0064 | 0x64 <-- notice most significant bit clear
*
* 32-bit -100 | 16-bit -100 | 8-bit -100
* 0xFFFFFF9C | 0xFF9C | 0x9C <-- notice most significant bit set
*
* The signed complication comes when going the other way. If the number is
* positive setting the most significant bytes to zero is correct. However
* if the number is negative the most significant bytes must be set to 0xFF.
* This is the process of sign-extension. Typically this is handled by the
* compiler. For example if a int16_t is assigned to an int32_t the compiler
* (or the processor instruction) knows to perform the sign extension. However
* in our case we can decode signed 24-bit numbers (for example) which are
* returned to the caller as int32_t. In this instance fielddecode performs the
* sign extension.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
//! Decode a null terminated string from a byte stream
void stringFromBytes(char* string, const uint8_t* bytes, int* index, int maxLength, int fixedLength);
//! Copy an array of bytes from a byte stream without changing the order.
void bytesFromBeBytes(uint8_t* data, const uint8_t* bytes, int* index, int num);
//! Copy an array of bytes from a byte stream while reversing the order.
void bytesFromLeBytes(uint8_t* data, const uint8_t* bytes, int* index, int num);
//! Decode a 4 byte float from a big endian byte stream.
float float32FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a 4 byte float from a little endian byte stream.
float float32FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 4 byte integer from a big endian byte stream.
uint32_t uint32FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 4 byte integer from a little endian byte stream.
uint32_t uint32FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a signed 4 byte integer from a big endian byte stream.
int32_t int32FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a signed 4 byte integer from a little endian byte stream.
int32_t int32FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 3 byte integer from a big endian byte stream.
uint32_t uint24FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 3 byte integer from a little endian byte stream.
uint32_t uint24FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a signed 3 byte integer from a big endian byte stream.
int32_t int24FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a signed 3 byte integer from a little endian byte stream.
int32_t int24FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 2 byte integer from a big endian byte stream.
uint16_t uint16FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 2 byte integer from a little endian byte stream.
uint16_t uint16FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a signed 2 byte integer from a big endian byte stream.
int16_t int16FromBeBytes(const uint8_t* bytes, int* index);
//! Decode a signed 2 byte integer from a little endian byte stream.
int16_t int16FromLeBytes(const uint8_t* bytes, int* index);
//! Decode a unsigned 1 byte integer from a byte stream.
#define uint8FromBytes(bytes, index) (uint8_t)((bytes)[(*(index))++])
//! Decode a signed 1 byte integer from a byte stream.
#define int8FromBytes(bytes, index) (int8_t)((bytes)[(*(index))++])
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,410 @@
// fieldencode.c was generated by ProtoGen version 2.18.c
#include "fieldencode.h"
/*!
* Encode a null terminated string on a byte stream
* \param string is the null termianted string to encode
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by the number of bytes encoded when this function
* is complete.
* \param maxLength is the maximum number of bytes that can be encoded. A null
* terminator is always included in the encoding.
* \param fixedLength should be 1 to force the number of bytes encoded to be
* exactly equal to maxLength.
*/
void stringToBytes(const char* string, uint8_t* bytes, int* index, int maxLength, int fixedLength)
{
int i;
// increment byte pointer for starting point
bytes += (*index);
// Reserve the last byte for null termination
for(i = 0; i < maxLength - 1; i++)
{
if(string[i] == 0)
break;
else
bytes[i] = (uint8_t)string[i];
}
// Make sure last byte has null termination
bytes[i++] = 0;
if(fixedLength)
{
// Finish with null bytes
for(; i < maxLength; i++)
bytes[i] = 0;
}
// Return for the number of bytes we encoded
(*index) += i;
}// stringToBytes
/*!
* Copy an array of bytes to a byte stream without changing the order.
* \param data is the array of bytes to copy.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by num when this function is complete.
* \param num is the number of bytes to copy
*/
void bytesToBeBytes(const uint8_t* data, uint8_t* bytes, int* index, int num)
{
// increment byte pointer for starting point
bytes += (*index);
// Increment byte index to indicate number of bytes copied
(*index) += num;
// Copy the bytes without changing the order
while(num > 0)
{
*(bytes++) = *(data++);
num--;
}
}// bytesToBeBytes
/*!
* Copy an array of bytes to a byte stream while reversing the order.
* \param data is the array of bytes to copy.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by num when this function is complete.
* \param num is the number of bytes to copy
*/
void bytesToLeBytes(const uint8_t* data, uint8_t* bytes, int* index, int num)
{
// increment byte pointer for starting point
bytes += (*index);
// Increment byte index to indicate number of bytes copied
(*index) += num;
// To encode as "little endian bytes", (a nonsensical statement), reverse the byte order
bytes += (num - 1);
// Copy the bytes, reversing the order
while(num > 0)
{
*(bytes--) = *(data++);
num--;
}
}// bytesToLeBytes
/*!
* Encode a 4 byte float on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
*/
void float32ToBeBytes(float number, uint8_t* bytes, int* index)
{
union
{
float floatValue;
uint32_t integerValue;
}field;
field.floatValue = number;
uint32ToBeBytes(field.integerValue, bytes, index);
}
/*!
* Encode a 4 byte float on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
*/
void float32ToLeBytes(float number, uint8_t* bytes, int* index)
{
union
{
float floatValue;
uint32_t integerValue;
}field;
field.floatValue = number;
uint32ToLeBytes(field.integerValue, bytes, index);
}
/*!
* Encode a unsigned 4 byte integer on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
*/
void uint32ToBeBytes(uint32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index) + 3;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 4;
}
/*!
* Encode a unsigned 4 byte integer on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
*/
void uint32ToLeBytes(uint32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index);
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 4;
}
/*!
* Encode a signed 4 byte integer on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
*/
void int32ToBeBytes(int32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index) + 3;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 4;
}
/*!
* Encode a signed 4 byte integer on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
*/
void int32ToLeBytes(int32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index);
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 4;
}
/*!
* Encode a unsigned 3 byte integer on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
*/
void uint24ToBeBytes(uint32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index) + 2;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 3;
}
/*!
* Encode a unsigned 3 byte integer on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
*/
void uint24ToLeBytes(uint32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index);
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 3;
}
/*!
* Encode a signed 3 byte integer on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
*/
void int24ToBeBytes(int32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index) + 2;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 3;
}
/*!
* Encode a signed 3 byte integer on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
*/
void int24ToLeBytes(int32_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index);
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 3;
}
/*!
* Encode a unsigned 2 byte integer on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
*/
void uint16ToBeBytes(uint16_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index) + 1;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 2;
}
/*!
* Encode a unsigned 2 byte integer on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
*/
void uint16ToLeBytes(uint16_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index);
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 2;
}
/*!
* Encode a signed 2 byte integer on a big endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
*/
void int16ToBeBytes(int16_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index) + 1;
*(bytes--) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 2;
}
/*!
* Encode a signed 2 byte integer on a little endian byte stream.
* \param number is the value to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
*/
void int16ToLeBytes(int16_t number, uint8_t* bytes, int* index)
{
// increment byte pointer for starting point
bytes += (*index);
*(bytes++) = (uint8_t)(number);
number = number >> 8;
*bytes = (uint8_t)(number);
(*index) += 2;
}
// end of fieldencode.c

View File

@ -0,0 +1,108 @@
// fieldencode.h was generated by ProtoGen version 2.18.c
#ifndef _FIELDENCODE_H
#define _FIELDENCODE_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
* fieldencode provides routines to place numbers into a byte stream.
*
* fieldencode provides routines to place numbers in local memory layout into
* a big or little endian byte stream. The byte stream is simply a sequence of
* bytes, as might come from the data payload of a packet.
*
* Support is included for non-standard types such as unsigned 24. When
* working with nonstandard types the data in memory are given using the next
* larger standard type. For example an unsigned 24 is actually a uint32_t in
* which the most significant byte is clear, and only the least significant
* three bytes are placed into a byte stream
*
* Big or Little Endian refers to the order that a computer architecture will
* place the bytes of a multi-byte word into successive memory locations. For
* example the 32-bit number 0x01020304 can be placed in successive memory
* locations in Big Endian: [0x01][0x02][0x03][0x04]; or in Little Endian:
* [0x04][0x03][0x02][0x01]. The names "Big Endian" and "Little Endian" come
* from Swift's Gulliver's travels, referring to which end of an egg should be
* opened. The choice of name is made to emphasize the degree to which the
* choice of memory layout is un-interesting, as long as one stays within the
* local memory.
*
* When transmitting data from one computer to another that assumption no
* longer holds. In computer-to-computer transmission there are three endians
* to consider: the endianness of the sender, the receiver, and the protocol
* between them. A protocol is Big Endian if it sends the most significant
* byte first and the least significant last. If the computer and the protocol
* have the same endianness then encoding data from memory into a byte stream
* is a simple copy. However if the endianness is not the same then bytes must
* be re-ordered for the data to be interpreted correctly.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
//! Encode a null terminated string on a byte stream
void stringToBytes(const char* string, uint8_t* bytes, int* index, int maxLength, int fixedLength);
//! Copy an array of bytes to a byte stream without changing the order.
void bytesToBeBytes(const uint8_t* data, uint8_t* bytes, int* index, int num);
//! Copy an array of bytes to a byte stream while reversing the order.
void bytesToLeBytes(const uint8_t* data, uint8_t* bytes, int* index, int num);
//! Encode a 4 byte float on a big endian byte stream.
void float32ToBeBytes(float number, uint8_t* bytes, int* index);
//! Encode a 4 byte float on a little endian byte stream.
void float32ToLeBytes(float number, uint8_t* bytes, int* index);
//! Encode a unsigned 4 byte integer on a big endian byte stream.
void uint32ToBeBytes(uint32_t number, uint8_t* bytes, int* index);
//! Encode a unsigned 4 byte integer on a little endian byte stream.
void uint32ToLeBytes(uint32_t number, uint8_t* bytes, int* index);
//! Encode a signed 4 byte integer on a big endian byte stream.
void int32ToBeBytes(int32_t number, uint8_t* bytes, int* index);
//! Encode a signed 4 byte integer on a little endian byte stream.
void int32ToLeBytes(int32_t number, uint8_t* bytes, int* index);
//! Encode a unsigned 3 byte integer on a big endian byte stream.
void uint24ToBeBytes(uint32_t number, uint8_t* bytes, int* index);
//! Encode a unsigned 3 byte integer on a little endian byte stream.
void uint24ToLeBytes(uint32_t number, uint8_t* bytes, int* index);
//! Encode a signed 3 byte integer on a big endian byte stream.
void int24ToBeBytes(int32_t number, uint8_t* bytes, int* index);
//! Encode a signed 3 byte integer on a little endian byte stream.
void int24ToLeBytes(int32_t number, uint8_t* bytes, int* index);
//! Encode a unsigned 2 byte integer on a big endian byte stream.
void uint16ToBeBytes(uint16_t number, uint8_t* bytes, int* index);
//! Encode a unsigned 2 byte integer on a little endian byte stream.
void uint16ToLeBytes(uint16_t number, uint8_t* bytes, int* index);
//! Encode a signed 2 byte integer on a big endian byte stream.
void int16ToBeBytes(int16_t number, uint8_t* bytes, int* index);
//! Encode a signed 2 byte integer on a little endian byte stream.
void int16ToLeBytes(int16_t number, uint8_t* bytes, int* index);
//! Encode a unsigned 1 byte integer on a byte stream.
#define uint8ToBytes(number, bytes, index) (bytes)[(*(index))++] = ((uint8_t)(number))
//! Encode a signed 1 byte integer on a byte stream.
#define int8ToBytes(number, bytes, index) (bytes)[(*(index))++] = ((int8_t)(number))
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,15 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

View File

@ -0,0 +1,278 @@
<?xml version="1.0"?>
<!--
This file provides the CAN protocol definition for the "ESC Velocity" speed controller manufactured by Currawong Engineering: https://www.currawongeng.com/servos-escs/esc-velocity/
-->
<Protocol name="ESCVelocity" prefix="ESC_" api="23" version="3.05" endian="big" supportSpecialFloat="false" supportInt64="false" supportFloat64="false" comment=
"This is the ICD for the Currawong Engineering Electronic Speed Controller (ESCVelocity). This document details the ESCVelocity command and packet structure for communication with and configuration of the ESC">
<Include name="string.h" comment="C string manipulation function header" global="true"/>
<Documentation name="Global ESC Enumerations" paragraph="1" comment="Packets in the protocol refer to these global enumerations."/>
<!-- TOP LEVEL ENUMERATIONS -->
<Enum name="ESCDisableSequence" comment="ESC_Disable_Sequence">
<Value name="ESC_DISABLE_A" value="0xAA" comment="Constant value required for disabling the ESC"/>
<Value name="ESC_DISABLE_B" value="0xC3" comment="Constant value required for disabling the ESC"/>
</Enum>
<Enum name="ESCEnableSequence" comment="ESC_Enable_Sequence">
<Value name="ESC_ENABLE_A" value="0xAA" comment="Constant value required for enabling the ESC"/>
<Value name="ESC_ENABLE_B" value="0x3C" comment="Constant value required for enabling the ESC"/>
</Enum>
<Enum name="ESCOperatingModes" prefix="ESC_MODE_" lookup="true" comment="ESC Operational Modes" description="These values define the various modes of operation of the ESC">
<Value name="STANDBY" value="0x00" comment="ESC is in standby mode - the motor is OFF but the ESC is ready to accept motor commands"/>
<Value name="PWM" comment="ESC is controlling motor in open-loop mode based on a 'PWM' (Pulse Width) input"/>
<Value name="RPM" comment="ESC is controlling motor speed based on an RPM setpoint"/>
<Value name="ESC_VALID_MODES" ignorePrefix="true" comment="ESC mode counter"/>
</Enum>
<Enum name="ESCCommandSources" prefix="ESC_COMMAND_SOURCE_" lookup="true" comment="ESC Command Sources" description="These values define the source that the ESC has received its most recent valid command from">
<Value name="NONE" value="0x00" comment="No valid command has been received"/>
<Value name="CAN" comment="Most recent command from CAN"/>
<Value name="PWM" comment="Most recent command from PWM"/>
</Enum>
<Enum name="ESCMotorTemperatureSensor" prefix="ESC_MOTOR_TEMP_SENSOR_" lookup="true" comment="ESC motor temperature sensor options">
<Value name="OFF" value="0x00" comment="No temperature sensor selected"/>
<Value name="KTY84" comment="KTY84 of equivalent"/>
<Value name="KTY83" comment="KTY83 or equivalent"/>
</Enum>
<Enum name="ESCCommandPriorities" prefix="ESC_COMMAND_PRIORITY_" lookup="true" comment="ESC Command Priorities">
<Value name="CAN_ONLY" value="0x00" comment="Commands only from CAN, PWM hardware input is disabled"/>
<Value name="CAN_PRIORITY" comment="Commands from CAN or PWM hardware input, CAN takes priority"/>
<Value name="PWM_PRIORITY" comment="Commands from CAN or PWM hardware input, PWM takes priority"/>
</Enum>
<Enum name="ESCMotorDirections" prefix="ESC_MOTOR_DIR_" comment="Motor Direction Enumeration">
<Value name="FORWARD" value="0x00" comment="Forward motor direction"/>
<Value name="REVERSE" value="0x01" comment="Reverse motor direction"/>
</Enum>
<Enum name="ESCBeepModes" prefix="ESC_BEEP_" comment="Motor beep modes enumeration">
<Value name="NONE" value="0b00"/>
<Value name="STATUS" value="0b01" comment="Motor status beeps only"/>
<Value name="ERROR" value="0b10" comment="Motor error beeps only"/>
<Value name="ALL" value="0b11" comment="All motor beeps"/>
</Enum>
<Documentation name="Packet IDs" paragraph="1" comment="Packet type definitions. Each packet has an 8-bit packet identifier (ID) which is used to identify the contents of the packet"/>
<Enum name="ESCMultiCommandPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Multi Command Packets" description="These packets can be used to send commands to 4 (four) ESCs with sequential CAN address identifiers, using a single CAN message. When sending these messages, they must be broadcast (using the special ESC broadcast address) so that each of the four target ESCs accept the CAN message.">
<Value name="SETPOINT_1" value ="0" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 1 - 4"/>
<Value name="SETPOINT_2" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 5 - 8"/>
<Value name="SETPOINT_3" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 9 - 12"/>
<Value name="SETPOINT_4" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 13 - 16"/>
<Value name="SETPOINT_5" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 17 - 20"/>
<Value name="SETPOINT_6" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 21 - 24"/>
<Value name="SETPOINT_7" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 25 - 28"/>
<Value name="SETPOINT_8" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 29 - 32"/>
<Value name="SETPOINT_9" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 33 - 36"/>
<Value name="SETPOINT_10" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 37 - 40"/>
<Value name="SETPOINT_11" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 41 - 44"/>
<Value name="SETPOINT_12" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 45 - 48"/>
<Value name="SETPOINT_13" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 49 - 52"/>
<Value name="SETPOINT_14" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 53 - 56"/>
<Value name="SETPOINT_15" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 57 - 60"/>
<Value name="SETPOINT_16" comment="This packet is used to send commands to multiple ESCs with sequential CAN IDs 61 - 64"/>
</Enum>
<Enum name="ESCCommandPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Command Packets" description="Command packets are sent to the ESC to change its operational mode. These packets **must** be fully implemented in the connected avionics system for complete operation of the PCU">
<Value name="PWM_CMD" value="0x10" comment="Send a PWM (Pulse width) command to a particular ESC"/>
<Value name="RPM_CMD" comment="Send an RPM (Speed) command to a particular ESC"/>
<Value name="DISABLE" value="0x20" comment="Send this packet to an ESC to disable the ESC"/>
<Value name="STANDBY" comment="Send this packet to an ESC to enable the ESC and place it in Standby mode"/>
</Enum>
<Enum name="ESCStatusPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Status Packets" description="Status packets are transmitted by the ESC at (user-configurable) intervals. These packets contain vital system information and should be fully implemented by the connected avionics device(s).">
<!-- Telemetry Packets -->
<Value name="STATUS_A" value="0x80" comment="ESC Status A telemetry packet transmitted by the ESC at regular intervals"/>
<Value name="STATUS_B" comment="ESC Status B telemetry packet transmitted by the ESC at regular intervals"/>
<Value name="ACCELEROMETER" value="0x88" comment="Raw accelerometer data"/>
</Enum>
<Enum name="ESCPackets" lookup="true" prefix="PKT_ESC_" comment="ESC Packets Definitions" description="ESC configuration packets. Each packet can be requested from the ESC by sending a zero-length packet of the same type.">
<!-- System information / settings packets -->
<Value name="SERIAL_NUMBER" value="0x90" comment="ESC Serial Number and User ID information"/>
<Value name="TITLE" comment="Human-readable string descriptor (max 8 chars) of the particular ESC"/>
<Value name="FIRMWARE" comment="ESC Firmware information"/>
<Value name="SYSTEM_INFO" comment="ESC system information packet"/>
<Value name="TELEMETRY_SETTINGS" comment="Telemetry packet configuration"/>
<Value name="EEPROM" comment="ESC non-volatile data information and settings"/>
</Enum>
<!-- ESC Status Bitfield -->
<Structure name="StatusBits" file="ESCDefines" comment="The *status* of the ESC is represented using these status bits. ESC system functionality can be quickly determined using these bits">
<Data name="hwInhibit" inMemoryType="bitfield1" comment="1 = Hardware inhibit is active (ESC is disabled)"/>
<Data name="swInhibit" inMemoryType="bitfield1" comment="1 = Software inhibit is active (ESC is disabled)"/>
<Data name="afwEnabled" inMemoryType="bitfield1" comment="0 = Active Freewheeling is not enabled, 1 = Active Freewheeling is enabled"/>
<Data name="direction" inMemoryType="bitfield1" comment="0 = Motor direction is FORWARDS, 1= Motor direction is REVERSE"/>
<Data name="timeout" inMemoryType="bitfield1" comment="Set if the ESC command timeout period has elapsed (and the ESC is in STANDBY mode)"/>
<Data name="starting" inMemoryType="bitfield1" comment="1 = in starting mode (0 = stopped or running)"/>
<Data name="commandSource" inMemoryType="bitfield1" comment="0 = most recent command from CAN, 1 = most recent command from PWM"/>
<Data name="running" inMemoryType="bitfield1" comment="ESC is running"/>
</Structure>
<Structure name="WarningBits" file="ESCDefines" comment="The *warning* bits enumerate various system warnings/errors of which the user (or user software) should be made aware. These *warning* bits are transmitted in the telemetry packets such that user software is aware of any these *warning* conditions and can poll the ESC for particular packets if any further information is needed. The ESC will continue to function in the case of a *warning* state">
<Data name="noRPMSignal" inMemoryType="bitfield1" comment="Set if RPM signal is not detected"/>
<Data name="overspeed" inMemoryType="bitfield1" comment="Set if the ESC motor speed exceeds the configured warning threshold"/>
<Data name="overcurrent" inMemoryType="bitfield1" comment="Set if the ESC motor current (positive or negative) exceeds the configured warning threshold"/>
<Data name="escTemperature" inMemoryType="bitfield1" comment="Set if the internal ESC temperature is above the warning threshold"/>
<Data name="motorTemperature" inMemoryType="bitfield1" comment="Set if the motor temperature is above the warning threshold"/>
<Data name="undervoltage" inMemoryType="bitfield1" comment="Set if the input voltage is below the minimum threshold"/>
<Data name="overvoltage" inMemoryType="bitfield1" comment="Set if the input voltage is above the maximum threshold"/>
<Data name="invalidPWMsignal" inMemoryType="bitfield1" comment="Set if hardware PWM input is enabled but invalid"/>
</Structure>
<Structure name="ErrorBits" file="ESCDefines" comment="The *error* bits enumerate critical system errors that will cause the ESC to stop functioning until the error cases are alleviated">
<Data name="linkError" inMemoryType="bitfield1" comment="Set if communication link to the motor controller is lost"/>
<Data name="foldback" inMemoryType="bitfield1" comment="Set if the ESC has detected an overcurrent event and is actively folding back duty cycle"/>
<Data name="settingsChecksum" inMemoryType="bitfield1" comment="Set if the settings checksum does not match the programmed values"/>
<Data name="motorSettings" inMemoryType="bitfield1" comment="Set if the motor settings are invalid"/>
<Data name="reservedD" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="reservedE" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="reservedF" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="reservedG" inMemoryType="bitfield1" comment="Reserved for future use"/>
</Structure>
<!-- Non-Volatile Settings Information -->
<Structure name="TelemetryPackets" file="ESCDefines" comment="These bits are used to determine which packets are automatically transmitted as telemetry data by the ESC. Only the packets described here can be configured as telemetry packets">
<Data name="statusA" inMemoryType="bitfield1" initialValue="1" comment="If this bit is set, the STATUS_A packet will be transmitted at the configured rate"/>
<Data name="statusB" inMemoryType="bitfield1" initialValue="1" comment="If this bit is set, the STATUS_B packet will be transmitted at the configured rate"/>
<Data name="statusC" inMemoryType="bitfield1" initialValue="1" comment="If this bit is set, the STATUS_C packet will be transmitted at the configured rate"/>
<Data name="accelerometer" inMemoryType="bitfield1" initialValue="0" comment="If this bit is set, the ACCELEROMETER packet will be transmitted at the configured rate"/>
<Data name="statusD" inMemoryType="bitfield1" comment="If this bit is set, the STATUS_D packet will be transmitted at the configured rate"/>
<Data name="reservedB" inMemoryType="bitfield1" comment="Reserved for future use"/>
<Data name="piccoloDownlink" inMemoryType="bitfield1" comment="If this bit is set, any STATUS_x packets selected for telemetry will be mirrored on the Piccolo Downlink packet group (0x14)"/>
<Data name="reservedD" inMemoryType="bitfield1" comment="Reserved for future use"/>
</Structure>
<!-- Command Packet Definitions Start Here -->
<Documentation name="Command Packets" paragraph="1" comment="These packets are sent to the ESC to command certain operational modes. The ESC does not acknowledge these packets"/>
<Packet name="CommandMultipleESCs"
ID="PKT_ESC_SETPOINT_1 PKT_ESC_SETPOINT_2 PKT_ESC_SETPOINT_3 PKT_ESC_SETPOINT_4 PKT_ESC_SETPOINT_5 PKT_ESC_SETPOINT_6"
file="ESCPackets" parameterInterface="true" comment="Send this packet to command ESCs which have CAN ID values in the range {1,4} (inclusive). This packet must be sent as a broadcast packet (address = 0xFF) such that all ESCs can receive it. Similiar commands are available for commanding ESCs with ID values up to 64, using different ESC_SETPOINT_x packet ID values.">
<Data name="pwmValueA" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 1" units="1us per bit"/>
<Data name="pwmValueB" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 2" units="1us per bit"/>
<Data name="pwmValueC" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 3" units="1us per bit"/>
<Data name="pwmValueD" inMemoryType="unsigned16" comment="The PWM (pulse width) command for ESC with CAN ID 4" units="1us per bit"/>
</Packet>
<Packet name="Disable" ID="PKT_ESC_DISABLE" file="ESCPackets" parameterInterface="true" comment="Send this packet to the ESC to disable it. The ESC will not accept PWM/RPM commands until it is re-enabled.">
<Data name="disableSequenceA" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_DISABLE_A" comment="This value must be set for the command to be accepted"/>
<Data name="disableSequenceB" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_DISABLE_B" comment="This value must be set for the command to be accepted"/>
</Packet>
<Packet name="Enable" ID="PKT_ESC_STANDBY" file="ESCPackets" parameterInterface="true" comment="Send this packet to the ESC to enable it. The ESC will be placed in Standby mode.">
<Data name="enableSequenceA" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_ENABLE_A" comment="This value must be set for the command to be accepted"/>
<Data name="enableSequenceB" inMemoryType="null" encodedType="unsigned8" checkConstant="true" constant="ESC_ENABLE_B" comment="This value must be set for the command to be included"/>
</Packet>
<Packet name="PWMCommand" ID="PKT_ESC_PWM_CMD" parameterInterface="true" file="ESCPackets" comment="Send a PWM (pulse width) command to an individual ESC. The pulse width value in specified in microseconds for compatibility with standard ESC interface. Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus.">
<Data name="pwmCommand" inMemoryType="unsigned16" comment="PWM command" units="1us per bit"/>
</Packet>
<Packet name="RPMCommand" ID="PKT_ESC_RPM_CMD" parameterInterface="true" file="ESCPackets" comment="Send an RPM (speed) command to an individual ESC. Use the broadcast ID (0xFF) to send this command to all ESCs on the CAN bus">
<Data name="rpmCommand" inMemoryType="unsigned16" comment="RPM Command" units="RPM"/>
</Packet>
<!--
STATUS PACKETS
-->
<Documentation name="Status Packets" paragraph="1" comment="These packets are transmitted by the ESC at a user-configurable rate. These packets contain operational data pertaining to the status of the ESC. Each packet can also be requested (polled) by sending a zero-length packet of the same type."/>
<Packet name="StatusA" ID="PKT_ESC_STATUS_A" file="ESCPackets" parameterInterface="true" structureInterface="true"
comment="The ESC_STATUS_A packet contains high-priority ESC status information. This packet is transmitted by the ESC at regular (user-configurable) intervals. It can also be requested (polled) from the ESC by sending a zero-length packet of the same type.">
<Data name="mode" inMemoryType="unsigned8" comment="ESC operating mode. The lower four bits indicate the operational mode of the ESC, in accordance with the ESCOperatingModes enumeration. The upper four bits are used for debugging and should be ignored for general use."/>
<Data name="status" struct="StatusBits" comment="ESC status bits"/>
<Data name="warnings" struct="WarningBits" comment="ESC warning bits"/>
<Data name="errors" struct="ErrorBits" comment="ESC *error* bits"/>
<Data name="command" inMemoryType="unsigned16" comment="ESC operational command - value depends on 'mode' available in this packet. If the ESC is disabled, data reads 0x0000. If the ESC is in open-loop PWM mode, this value is the PWM command in units of 1us, in the range 1000us to 2000us. If the ESC is in closed-loop RPM mode, this value is the RPM command in units of 1RPM"/>
<Data name="rpm" inMemoryType="unsigned16" comment="Motor speed" units="1RPM per bit"/>
</Packet>
<Packet name="StatusB" ID="PKT_ESC_STATUS_B" file="ESCPackets" parameterInterface="true" structureInterface="true"
comment="The ESC_STATUS_B packet contains ESC operational information. This packet is transmitted by the ESC at regular (user-configurable) intervals. It can also be requested (polled) from the ESC by sending a zero-length packet of the same type.">
<Data name="voltage" inMemoryType="unsigned16" comment="ESC Rail Voltage" units="0.1V per bit"/>
<Data name="current" inMemoryType="signed16" units="0.1A per bit" comment="ESC Current. Current IN to the ESC is positive. Current OUT of the ESC is negative"/>
<Data name="dutyCycle" inMemoryType="unsigned16" comment="ESC Motor Duty Cycle" units="0.1% per bit"/>
<Data name="escTemperature" inMemoryType="signed8" comment="ESC Board Temperature" units="1 degree C per bit" range="-128C to +127C"/>
<Data name="motorTemperature" inMemoryType="unsigned8" comment="ESC Motor Temperature" units="1 degree C per bit" range="-50 to +205 (0 = -50C)"/>
</Packet>
<Packet name="Accelerometer" ID="PKT_ESC_ACCELEROMETER" parameterInterface="true" structureInterface="true" file="ESCPackets"
comment="This packet contains raw accelerometer data from the ESC. It can be requested (polled) from the ESC by sending a zero-length packet of the same type. It can also be transmitted by the ESC at high-frequency using the high-frequency streaming functionality of the ESC">
<Data name="xAcc" inMemoryType="signed16" comment="X axis acceleration value" range="-0x7FFF to +0x7FFF" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units"/>
<Data name="yAcc" inMemoryType="signed16" comment="Y axis acceleration value" range="-0x7FFF to +0x7FFF" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units"/>
<Data name="zAcc" inMemoryType="signed16" comment="Z axis acceleration value" range="-0x7FFF to +0x7FFF" notes="Multiply by (0.5 * fullscale / 2^resolution) to get acceleration value in 'g' units"/>
<Data name="fullscale" inMemoryType="unsigned8" comment="Accelerometer full-scale range"/>
<Data name="resolution" inMemoryType="unsigned8" comment="Accelerometer measurement resolution, in 'bits'."/>
</Packet>
<!-- System info / settings packets -->
<Documentation name="Config Packets" paragraph="1" comment="These packets provide information on the ESC system status, and allow the avionics device and/or operator to determine that the ESC is correctly configured prior to flight. To request these config packets, send a zero-length packet with the same ID to the ESC. Note: For complete ESC configuration use the cEQUIP software provided by Currawong Engineering"/>
<Packet name="Address" ID="PKT_ESC_SERIAL_NUMBER" file="ESCPackets" structureInterface="true" parameterInterface="true" comment="This packet contains the serial number for the ESC. Additionally there are two extra values (each 16-bit) which can be programmed by the user for any purpose.">
<!-- The serial number was previously transmitted at 32-bit (but we are overriding the top byte to be hardware revision)
For backwards compatibility, the first byte in the packet must be used so the packet definitions are not corrupted. -->
<Data name="HardwareRevision" inMemoryType="unsigned8" comment="ESC hardware revision"/>
<Data name="SerialNumber" inMemoryType="unsigned32" encodedType="unsigned24" comment="ESC Serial Number (OTP - not configurable by user)"/>
<Data name="UserIDA" inMemoryType="unsigned16" comment="User ID Value A - user can set this value to any value"/>
<Data name="UserIDB" inMemoryType="unsigned16" comment="User ID Value B - user can set this value to any value"/>
</Packet>
<Packet name="Title" ID="PKT_ESC_TITLE" file="ESCPackets" parameterInterface="true" comment="This packet contains a zero-terminated string (max-length 8) used to identify the particular ESC.">
<Data name="ESCTitle" inMemoryType="unsigned8" array="8" comment="Description of this ESC"/>
</Packet>
<Packet name="Firmware" ID="PKT_ESC_FIRMWARE" file="ESCPackets" structureInterface="true" parameterInterface="true"
comment="This packet contains the firmware version of the ESC">
<Data name="versionMajor" inMemoryType="unsigned8" comment="Major firmware version number"/>
<Data name="versionMinor" inMemoryType="unsigned8" comment="Minor firmware version numner"/>
<Data name="versionDay" inMemoryType="unsigned8" comment="Firmware release date, day-of-month" range="1-31"/>
<Data name="versionMonth" inMemoryType="unsigned8" comment="Firmware release data, month-of-year" range="1-12"/>
<Data name="versionYear" inMemoryType="unsigned16" comment="Firmware release date, year"/>
<Data name="firmwareChecksum" inMemoryType="unsigned16" comment="Firmware checksum"/>
</Packet>
<Packet name="SystemInfo" ID="PKT_ESC_SYSTEM_INFO" file="ESCPackets" structureInterface="true" parameterInterface="true"
comment="This packet contains system runtime information">
<Data name="millisecondsSinceReset" inMemoryType="unsigned32" comment="Number of milliseconds since the ESC last experienced a reset/power-on event"/>
<Data name="powerCycles" inMemoryType="unsigned16" comment="Number of power cycle events that the ESC has experienced"/>
<Data name="resetCode" inMemoryType="unsigned8" comment="Processor RESET code for debug purposes"/>
<Data name="cpuOccupancy" inMemoryType="unsigned8" comment="Processor usage" units="1% per bit"/>
</Packet>
<Packet name="TelemetryConfig" ID="PKT_ESC_TELEMETRY_SETTINGS" useInOtherPackets="true" file="ESCPackets" structureInterface="true" parameterInterface="true" comment="Telemetry settings (storage class)" hidden="true">
<Data name="period" inMemoryType="unsigned8" comment="Telemetry period" units="50ms per bit" range="0 - 250 (0.0s to 25.0s)" initialValue="4" verifyMaxValue="250" notes="0 = Telemetry disabled"/>
<Data name="silence" inMemoryType="unsigned8" comment="Telemetry silence period (delay after RESET before telemetry data is sent)" units="50ms per bit" initialValue="20" verifyMaxValue="250" range="0 - 250 (0.0s to 25.0s)"/>
<Data name="packets" struct="TelemetryPackets" comment="Bitfield describing which telemetry packets are enabled"/>
</Packet>
<Packet name="TelemetrySettings" ID="PKT_ESC_TELEMETRY_SETTINGS" file="ESCPackets" parameterInterface="true" comment="This packet contains the telemetry packet configuration">
<Data name="settings" struct="TelemetryConfig" comment="Telemetry settings"/>
<Data name="apiVersion" inMemoryType="string" array="5" constant="getESCVelocityVersion()" comment="The API version of the ESC"/>
</Packet>
<Packet name="EEPROMSettings" ID="PKT_ESC_EEPROM" file="ESCPackets" parameterInterface="true" structureInterface="true"
comment="This packet contains information on the non-volatile ESC settings">
<Data name="version" inMemoryType="unsigned8" comment="Version of EEPROM data"/>
<Data name="size" inMemoryType="unsigned16" comment="Size of settings data"/>
<Data name="checksum" inMemoryType="unsigned16" comment="Settings checksum"/>
</Packet>
</Protocol>

View File

@ -0,0 +1,238 @@
// scaleddecode.c was generated by ProtoGen version 2.18.c
#include "scaleddecode.h"
#include "fielddecode.h"
/*!
* Inverse scale the bitfield base integer type to a float32
* \param value is the integer number to inverse scale
* \param min is the minimum value that can be represented.
* \param invscaler is multiplied by the integer to create the return value.
* invscaler should be the inverse of the scaler given to the scaling function.
* \return the correctly scaled decoded value. return = min + value*invscaler.
*/
float float32ScaledFromBitfield(unsigned int value, float min, float invscaler)
{
return (float)(min + invscaler*value);
}
/*!
* Compute a float scaled from 4 unsigned bytes in big endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom4UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint32FromBeBytes(bytes, index));
}
/*!
* Compute a float scaled from 4 unsigned bytes in little endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom4UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint32FromLeBytes(bytes, index));
}
/*!
* Compute a float scaled from 4 signed bytes in big endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom4SignedBeBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int32FromBeBytes(bytes, index));
}
/*!
* Compute a float scaled from 4 signed bytes in little endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom4SignedLeBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int32FromLeBytes(bytes, index));
}
/*!
* Compute a float scaled from 3 unsigned bytes in big endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom3UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint24FromBeBytes(bytes, index));
}
/*!
* Compute a float scaled from 3 unsigned bytes in little endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom3UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint24FromLeBytes(bytes, index));
}
/*!
* Compute a float scaled from 3 signed bytes in big endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom3SignedBeBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int24FromBeBytes(bytes, index));
}
/*!
* Compute a float scaled from 3 signed bytes in little endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom3SignedLeBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int24FromLeBytes(bytes, index));
}
/*!
* Compute a float scaled from 2 unsigned bytes in big endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint16FromBeBytes(bytes, index));
}
/*!
* Compute a float scaled from 2 unsigned bytes in little endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint16FromLeBytes(bytes, index));
}
/*!
* Compute a float scaled from 2 signed bytes in big endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int16FromBeBytes(bytes, index));
}
/*!
* Compute a float scaled from 2 signed bytes in little endian order.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int16FromLeBytes(bytes, index));
}
/*!
* Compute a float scaled from 1 unsigned byte.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 1 when this function is complete.
* \param min is the minimum value that can be decoded.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = min + encoded*invscaler.
*/
float float32ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, float min, float invscaler)
{
return (float)(min + invscaler*uint8FromBytes(bytes, index));
}
/*!
* Compute a float scaled from 1 signed byte.
* \param bytes is a pointer to the byte stream to decode.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 1 when this function is complete.
* \param invscaler is multiplied by the encoded integer to create the return value.
* invscaler should be the inverse of the scaler given to the encode function.
* \return the correctly scaled decoded value. return = encoded*invscaler.
*/
float float32ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, float invscaler)
{
return (float)(invscaler*int8FromBytes(bytes, index));
}
// end of scaleddecode.c

View File

@ -0,0 +1,69 @@
// scaleddecode.h was generated by ProtoGen version 2.18.c
#ifndef _SCALEDDECODE_H
#define _SCALEDDECODE_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
* scaleddecode routines extract scaled numbers from a byte stream.
*
* scaleddecode routines extract scaled numbers from a byte stream. The routines
* in this module are the reverse operation of the routines in scaledencode.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
//! Inverse scale the bitfield base integer type to a float32
float float32ScaledFromBitfield(unsigned int value, float min, float invscaler);
//! Compute a float scaled from 4 unsigned bytes in big endian order.
float float32ScaledFrom4UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 4 unsigned bytes in little endian order.
float float32ScaledFrom4UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 4 signed bytes in big endian order.
float float32ScaledFrom4SignedBeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 4 signed bytes in little endian order.
float float32ScaledFrom4SignedLeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 3 unsigned bytes in big endian order.
float float32ScaledFrom3UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 3 unsigned bytes in little endian order.
float float32ScaledFrom3UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 3 signed bytes in big endian order.
float float32ScaledFrom3SignedBeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 3 signed bytes in little endian order.
float float32ScaledFrom3SignedLeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 2 unsigned bytes in big endian order.
float float32ScaledFrom2UnsignedBeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 2 unsigned bytes in little endian order.
float float32ScaledFrom2UnsignedLeBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 2 signed bytes in big endian order.
float float32ScaledFrom2SignedBeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 2 signed bytes in little endian order.
float float32ScaledFrom2SignedLeBytes(const uint8_t* bytes, int* index, float invscaler);
//! Compute a float scaled from 1 unsigned byte.
float float32ScaledFrom1UnsignedBytes(const uint8_t* bytes, int* index, float min, float invscaler);
//! Compute a float scaled from 1 signed byte.
float float32ScaledFrom1SignedBytes(const uint8_t* bytes, int* index, float invscaler);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,467 @@
// scaledencode.c was generated by ProtoGen version 2.18.c
#include "scaledencode.h"
#include "fieldencode.h"
/*!
* Scale a float32 to the base integer type used for bitfield
* \param value is the number to scale.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the integer.
* \return (value-min)*scaler.
*/
unsigned int float32ScaledToBitfield(float value, float min, float scaler)
{
// Protect from underflow, overflow must be handled by caller
if(value < min)
return 0;
// scale the number
value = (value - min)*scaler;
// account for fractional truncation
return (unsigned int)(value + 0.5f);
}
/*!
* Encode a float on a byte stream by scaling to fit in 4 unsigned bytes in big
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo4UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint32_t number;
// Make sure number fits in the range
if(scaledvalue >= 4294967295uL)
number = 4294967295uL;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint32_t)(scaledvalue + 0.5f); // account for fractional truncation
uint32ToBeBytes((uint32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 4 unsigned bytes in
* little endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo4UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint32_t number;
// Make sure number fits in the range
if(scaledvalue >= 4294967295uL)
number = 4294967295uL;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint32_t)(scaledvalue + 0.5f); // account for fractional truncation
uint32ToLeBytes((uint32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 4 signed bytes in big
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo4SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int32_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 2147483647)
number = 2147483647;
else
number = (int32_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-2147483647 - 1))
number = (-2147483647 - 1);
else
number = (int32_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int32ToBeBytes((int32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 4 signed bytes in little
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 4 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo4SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int32_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 2147483647)
number = 2147483647;
else
number = (int32_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-2147483647 - 1))
number = (-2147483647 - 1);
else
number = (int32_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int32ToLeBytes((int32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 3 unsigned bytes in big
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo3UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint32_t number;
// Make sure number fits in the range
if(scaledvalue >= 16777215u)
number = 16777215u;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint32_t)(scaledvalue + 0.5f); // account for fractional truncation
uint24ToBeBytes((uint32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 3 unsigned bytes in
* little endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo3UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint32_t number;
// Make sure number fits in the range
if(scaledvalue >= 16777215u)
number = 16777215u;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint32_t)(scaledvalue + 0.5f); // account for fractional truncation
uint24ToLeBytes((uint32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 3 signed bytes in big
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo3SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int32_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 8388607)
number = 8388607;
else
number = (int32_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-8388607 - 1))
number = (-8388607 - 1);
else
number = (int32_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int24ToBeBytes((int32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 3 signed bytes in little
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 3 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo3SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int32_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 8388607)
number = 8388607;
else
number = (int32_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-8388607 - 1))
number = (-8388607 - 1);
else
number = (int32_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int24ToLeBytes((int32_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 2 unsigned bytes in big
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo2UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint16_t number;
// Make sure number fits in the range
if(scaledvalue >= 65535u)
number = 65535u;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint16_t)(scaledvalue + 0.5f); // account for fractional truncation
uint16ToBeBytes((uint16_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 2 unsigned bytes in
* little endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo2UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint16_t number;
// Make sure number fits in the range
if(scaledvalue >= 65535u)
number = 65535u;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint16_t)(scaledvalue + 0.5f); // account for fractional truncation
uint16ToLeBytes((uint16_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 2 signed bytes in big
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo2SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int16_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 32767)
number = 32767;
else
number = (int16_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-32767 - 1))
number = (-32767 - 1);
else
number = (int16_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int16ToBeBytes((int16_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 2 signed bytes in little
* endian order.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 2 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo2SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int16_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 32767)
number = 32767;
else
number = (int16_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-32767 - 1))
number = (-32767 - 1);
else
number = (int16_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int16ToLeBytes((int16_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 1 unsigned byte.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 1 when this function is complete.
* \param min is the minimum value that can be encoded.
* \param scaler is multiplied by value to create the encoded integer: encoded = (value-min)*scaler.
*/
void float32ScaledTo1UnsignedBytes(float value, uint8_t* bytes, int* index, float min, float scaler)
{
// scale the number
float scaledvalue = (float)((value - min)*scaler);
uint8_t number;
// Make sure number fits in the range
if(scaledvalue >= 255u)
number = 255u;
else if(scaledvalue <= 0)
number = 0;
else
number = (uint8_t)(scaledvalue + 0.5f); // account for fractional truncation
uint8ToBytes((uint8_t)number, bytes, index);
}
/*!
* Encode a float on a byte stream by scaling to fit in 1 signed byte.
* \param value is the number to encode.
* \param bytes is a pointer to the byte stream which receives the encoded data.
* \param index gives the location of the first byte in the byte stream, and
* will be incremented by 1 when this function is complete.
* \param scaler is multiplied by value to create the encoded integer: encoded = value*scaler.
*/
void float32ScaledTo1SignedBytes(float value, uint8_t* bytes, int* index, float scaler)
{
// scale the number
float scaledvalue = (float)(value*scaler);
int8_t number;
// Make sure number fits in the range
if(scaledvalue >= 0)
{
if(scaledvalue >= 127)
number = 127;
else
number = (int8_t)(scaledvalue + 0.5f); // account for fractional truncation
}
else
{
if(scaledvalue <= (-127 - 1))
number = (-127 - 1);
else
number = (int8_t)(scaledvalue - 0.5f); // account for fractional truncation
}
int8ToBytes((int8_t)number, bytes, index);
}
// end of scaledencode.c

View File

@ -0,0 +1,102 @@
// scaledencode.h was generated by ProtoGen version 2.18.c
#ifndef _SCALEDENCODE_H
#define _SCALEDENCODE_H
// C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
* scaledencode routines place scaled numbers into a byte stream.
*
* scaledencode routines place scaled values into a big or little endian byte
* stream. The values can be any legitimate type (double, float, uint32_t,
* uint16_t, uint8_t, int32_t, int16_t, int8_t), and are encoded as either a
* unsigned or signed integer from 1 to 8 bytes in length. Unsigned encodings
* allow the caller to specify a minimum and a maximum value, with the only
* limitation that the maximum value must be more than the minimum. Signed
* encodings only allow the caller to specify a maximum value which gives
* maximum absolute value that can be encoded.
*
* An example encoding would be: take a float that represents speed in meters
* per second and encode it in two bytes from -200 to 200 meters per second.
* In that example the encoding function would be:
*
* floatScaledTo2SignedBeBytes(speed, bytestream, &index, 200);
*
* This would scale the speed according to (32767/200), and copy the resulting
* two bytes to bytestream[index] as a signed 16 bit number in big endian
* order. This would result in a velocity resolution of 0.006 m/s.
*
* Another example encoding is: take a double that represents altitude in
* meters and encode it in three bytes from -1000 to 49000 meters:
*
* doubleScaledTo3UnsignedLeBytes(alt, bytestream, &index, -1000, 49000);
*
* This would transform the altitude according to (alt *(16777215/50000) + 1000)
* and copy the resulting three bytes to bytestream[index] as an unsigned 24
* bit number in little endian order. This would result in an altitude
* resolution of 0.003 meters.
*
* scaledencode does not include routines that increase the resolution of the
* source value. For example the function floatScaledTo5UnsignedBeBytes() does
* not exist, because expanding a float to 5 bytes does not make any resolution
* improvement over encoding it in 4 bytes. In general the encoded format
* must be equal to or less than the number of bytes of the raw data.
*/
#define __STDC_CONSTANT_MACROS
#include <stdint.h>
//! Scale a float32 to the base integer type used for bitfield
unsigned int float32ScaledToBitfield(float value, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 unsigned bytes in big endian order.
void float32ScaledTo4UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 unsigned bytes in little endian order.
void float32ScaledTo4UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 signed bytes in big endian order.
void float32ScaledTo4SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 4 signed bytes in little endian order.
void float32ScaledTo4SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 unsigned bytes in big endian order.
void float32ScaledTo3UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 unsigned bytes in little endian order.
void float32ScaledTo3UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 signed bytes in big endian order.
void float32ScaledTo3SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 3 signed bytes in little endian order.
void float32ScaledTo3SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 unsigned bytes in big endian order.
void float32ScaledTo2UnsignedBeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 unsigned bytes in little endian order.
void float32ScaledTo2UnsignedLeBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 signed bytes in big endian order.
void float32ScaledTo2SignedBeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 2 signed bytes in little endian order.
void float32ScaledTo2SignedLeBytes(float value, uint8_t* bytes, int* index, float scaler);
//! Encode a float on a byte stream by scaling to fit in 1 unsigned byte.
void float32ScaledTo1UnsignedBytes(float value, uint8_t* bytes, int* index, float min, float scaler);
//! Encode a float on a byte stream by scaling to fit in 1 signed byte.
void float32ScaledTo1SignedBytes(float value, uint8_t* bytes, int* index, float scaler);
#ifdef __cplusplus
}
#endif
#endif