ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/TransmuterPackets.h

710 lines
32 KiB
C

// TransmuterPackets.h was generated by ProtoGen version 3.5.c
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Oliver Walters / Currawong Engineering Pty Ltd
*/
#ifndef _TRANSMUTERPACKETS_H
#define _TRANSMUTERPACKETS_H
// Language target is C, C++ compilers: don't mangle us
#ifdef __cplusplus
extern "C" {
#endif
/*!
* \file
*/
#include <stdint.h>
#include <stdbool.h>
#include "TransmuterProtocol.h"
#include "TransmuterDefines.h"
//! Create the Transmuter_EnterStandby packet from parameters
void encodeTransmuter_EnterStandbyPacket(void* pkt);
//! Decode the Transmuter_EnterStandby packet to parameters
int decodeTransmuter_EnterStandbyPacket(const void* pkt);
//! return the packet ID for the Transmuter_EnterStandby packet
#define getTransmuter_EnterStandbyPacketID() (PKT_TRANSMUTER_STANDBY)
//! return the minimum encoded length for the Transmuter_EnterStandby packet
#define getTransmuter_EnterStandbyMinDataLength() (2)
//! return the maximum encoded length for the Transmuter_EnterStandby packet
#define getTransmuter_EnterStandbyMaxDataLength() (2)
//! Create the Transmuter_EnterPreflight packet from parameters
void encodeTransmuter_EnterPreflightPacket(void* pkt);
//! Decode the Transmuter_EnterPreflight packet to parameters
int decodeTransmuter_EnterPreflightPacket(const void* pkt);
//! return the packet ID for the Transmuter_EnterPreflight packet
#define getTransmuter_EnterPreflightPacketID() (PKT_TRANSMUTER_PREFLIGHT)
//! return the minimum encoded length for the Transmuter_EnterPreflight packet
#define getTransmuter_EnterPreflightMinDataLength() (2)
//! return the maximum encoded length for the Transmuter_EnterPreflight packet
#define getTransmuter_EnterPreflightMaxDataLength() (2)
//! Create the Transmuter_EnterWarmup packet from parameters
void encodeTransmuter_EnterWarmupPacket(void* pkt);
//! Decode the Transmuter_EnterWarmup packet to parameters
int decodeTransmuter_EnterWarmupPacket(const void* pkt);
//! return the packet ID for the Transmuter_EnterWarmup packet
#define getTransmuter_EnterWarmupPacketID() (PKT_TRANSMUTER_WARMUP)
//! return the minimum encoded length for the Transmuter_EnterWarmup packet
#define getTransmuter_EnterWarmupMinDataLength() (2)
//! return the maximum encoded length for the Transmuter_EnterWarmup packet
#define getTransmuter_EnterWarmupMaxDataLength() (2)
//! Create the Transmuter_EnterRunMode packet from parameters
void encodeTransmuter_EnterRunModePacket(void* pkt);
//! Decode the Transmuter_EnterRunMode packet to parameters
int decodeTransmuter_EnterRunModePacket(const void* pkt);
//! return the packet ID for the Transmuter_EnterRunMode packet
#define getTransmuter_EnterRunModePacketID() (PKT_TRANSMUTER_RUN)
//! return the minimum encoded length for the Transmuter_EnterRunMode packet
#define getTransmuter_EnterRunModeMinDataLength() (2)
//! return the maximum encoded length for the Transmuter_EnterRunMode packet
#define getTransmuter_EnterRunModeMaxDataLength() (2)
//! Create the Transmuter_EnterPWMMode packet from parameters
void encodeTransmuter_EnterPWMModePacket(void* pkt);
//! Decode the Transmuter_EnterPWMMode packet to parameters
int decodeTransmuter_EnterPWMModePacket(const void* pkt);
//! return the packet ID for the Transmuter_EnterPWMMode packet
#define getTransmuter_EnterPWMModePacketID() (PKT_TRANSMUTER_PWM)
//! return the minimum encoded length for the Transmuter_EnterPWMMode packet
#define getTransmuter_EnterPWMModeMinDataLength() (2)
//! return the maximum encoded length for the Transmuter_EnterPWMMode packet
#define getTransmuter_EnterPWMModeMaxDataLength() (2)
/*!
* The TelemetryStatus packet contains critical operational status information
* pertaining to the current state of the Transmuter
*/
typedef struct
{
Transmuter_StatusBits_t status;
Transmuter_WarningBits_t warning;
Transmuter_ErrorBits_t errors;
}Transmuter_TelemetryStatus_t;
//! Create the Transmuter_TelemetryStatus packet
void encodeTransmuter_TelemetryStatusPacketStructure(void* pkt, const Transmuter_TelemetryStatus_t* user);
//! Decode the Transmuter_TelemetryStatus packet
int decodeTransmuter_TelemetryStatusPacketStructure(const void* pkt, Transmuter_TelemetryStatus_t* user);
//! Create the Transmuter_TelemetryStatus packet from parameters
void encodeTransmuter_TelemetryStatusPacket(void* pkt, const Transmuter_StatusBits_t* status, const Transmuter_WarningBits_t* warning, const Transmuter_ErrorBits_t* errors);
//! Decode the Transmuter_TelemetryStatus packet to parameters
int decodeTransmuter_TelemetryStatusPacket(const void* pkt, Transmuter_StatusBits_t* status, Transmuter_WarningBits_t* warning, Transmuter_ErrorBits_t* errors);
//! return the packet ID for the Transmuter_TelemetryStatus packet
#define getTransmuter_TelemetryStatusPacketID() (PKT_TRANSMUTER_TELEMETRY_STATUS)
//! return the minimum encoded length for the Transmuter_TelemetryStatus packet
#define getTransmuter_TelemetryStatusMinDataLength() (8)
//! return the maximum encoded length for the Transmuter_TelemetryStatus packet
#define getTransmuter_TelemetryStatusMaxDataLength() (8)
/*!
* The TelemetryPower packet contains information on the current operation
* point of the engine and generator
*/
typedef struct
{
float voltage; //!< System voltage
float genCurrent; //!< Generator current
float batCurrent; //!< Battery current
int16_t rpm; //!< Mechanical rotational speed
}Transmuter_TelemetryPower_t;
//! Create the Transmuter_TelemetryPower packet
void encodeTransmuter_TelemetryPowerPacketStructure(void* pkt, const Transmuter_TelemetryPower_t* user);
//! Decode the Transmuter_TelemetryPower packet
int decodeTransmuter_TelemetryPowerPacketStructure(const void* pkt, Transmuter_TelemetryPower_t* user);
//! Create the Transmuter_TelemetryPower packet from parameters
void encodeTransmuter_TelemetryPowerPacket(void* pkt, float voltage, float genCurrent, float batCurrent, int16_t rpm);
//! Decode the Transmuter_TelemetryPower packet to parameters
int decodeTransmuter_TelemetryPowerPacket(const void* pkt, float* voltage, float* genCurrent, float* batCurrent, int16_t* rpm);
//! return the packet ID for the Transmuter_TelemetryPower packet
#define getTransmuter_TelemetryPowerPacketID() (PKT_TRANSMUTER_TELEMETRY_POWER)
//! return the minimum encoded length for the Transmuter_TelemetryPower packet
#define getTransmuter_TelemetryPowerMinDataLength() (8)
//! return the maximum encoded length for the Transmuter_TelemetryPower packet
#define getTransmuter_TelemetryPowerMaxDataLength() (8)
/*!
* The TelemetrySetpoint packet contains system setpoint/target information
*/
typedef struct
{
float currentSetpoint; //!< Battery current setpoint value
int16_t rpmTarget; //!< System RPM target
uint8_t throttleTarget; //!< ECU throttle target
int16_t powerTarget; //!< Generator power target
}Transmuter_TelemetrySetpoint_t;
//! Create the Transmuter_TelemetrySetpoint packet
void encodeTransmuter_TelemetrySetpointPacketStructure(void* pkt, const Transmuter_TelemetrySetpoint_t* user);
//! Decode the Transmuter_TelemetrySetpoint packet
int decodeTransmuter_TelemetrySetpointPacketStructure(const void* pkt, Transmuter_TelemetrySetpoint_t* user);
//! Create the Transmuter_TelemetrySetpoint packet from parameters
void encodeTransmuter_TelemetrySetpointPacket(void* pkt, float currentSetpoint, int16_t rpmTarget, uint8_t throttleTarget, int16_t powerTarget);
//! Decode the Transmuter_TelemetrySetpoint packet to parameters
int decodeTransmuter_TelemetrySetpointPacket(const void* pkt, float* currentSetpoint, int16_t* rpmTarget, uint8_t* throttleTarget, int16_t* powerTarget);
//! return the packet ID for the Transmuter_TelemetrySetpoint packet
#define getTransmuter_TelemetrySetpointPacketID() (PKT_TRANSMUTER_TELEMETRY_SETPOINT)
//! return the minimum encoded length for the Transmuter_TelemetrySetpoint packet
#define getTransmuter_TelemetrySetpointMinDataLength() (7)
//! return the maximum encoded length for the Transmuter_TelemetrySetpoint packet
#define getTransmuter_TelemetrySetpointMaxDataLength() (7)
/*!
* The TelemetryGenerator packet provides information about the current
* operational status of the generator and EFI system.
*/
typedef struct
{
uint8_t fetTemperature; //!< Power electronics module temperature
uint8_t motTemperature; //!< Generator motor temperature
uint8_t chtTemperature; //!< Engine cylinder head temperature
float fuelPressure; //!< Fuel pressure
}Transmuter_TelemetryGenerator_t;
//! Create the Transmuter_TelemetryGenerator packet
void encodeTransmuter_TelemetryGeneratorPacketStructure(void* pkt, const Transmuter_TelemetryGenerator_t* user);
//! Decode the Transmuter_TelemetryGenerator packet
int decodeTransmuter_TelemetryGeneratorPacketStructure(const void* pkt, Transmuter_TelemetryGenerator_t* user);
//! Create the Transmuter_TelemetryGenerator packet from parameters
void encodeTransmuter_TelemetryGeneratorPacket(void* pkt, uint8_t fetTemperature, uint8_t motTemperature, uint8_t chtTemperature, float fuelPressure);
//! Decode the Transmuter_TelemetryGenerator packet to parameters
int decodeTransmuter_TelemetryGeneratorPacket(const void* pkt, uint8_t* fetTemperature, uint8_t* motTemperature, uint8_t* chtTemperature, float* fuelPressure);
//! return the packet ID for the Transmuter_TelemetryGenerator packet
#define getTransmuter_TelemetryGeneratorPacketID() (PKT_TRANSMUTER_TELEMETRY_GEN)
//! return the minimum encoded length for the Transmuter_TelemetryGenerator packet
#define getTransmuter_TelemetryGeneratorMinDataLength() (5)
//! return the maximum encoded length for the Transmuter_TelemetryGenerator packet
#define getTransmuter_TelemetryGeneratorMaxDataLength() (5)
/*!
* The TelemetryCapacity packet provides information on the battery and fuel
* capacity
*/
typedef struct
{
uint32_t fuelUsed; //!< Fuel used estimate
}Transmuter_TelemetryCapacity_t;
//! Create the Transmuter_TelemetryCapacity packet
void encodeTransmuter_TelemetryCapacityPacketStructure(void* pkt, const Transmuter_TelemetryCapacity_t* user);
//! Decode the Transmuter_TelemetryCapacity packet
int decodeTransmuter_TelemetryCapacityPacketStructure(const void* pkt, Transmuter_TelemetryCapacity_t* user);
//! Create the Transmuter_TelemetryCapacity packet from parameters
void encodeTransmuter_TelemetryCapacityPacket(void* pkt, uint32_t fuelUsed);
//! Decode the Transmuter_TelemetryCapacity packet to parameters
int decodeTransmuter_TelemetryCapacityPacket(const void* pkt, uint32_t* fuelUsed);
//! return the packet ID for the Transmuter_TelemetryCapacity packet
#define getTransmuter_TelemetryCapacityPacketID() (PKT_TRANSMUTER_TELEMETRY_CAPACITY)
//! return the minimum encoded length for the Transmuter_TelemetryCapacity packet
#define getTransmuter_TelemetryCapacityMinDataLength() (4)
//! return the maximum encoded length for the Transmuter_TelemetryCapacity packet
#define getTransmuter_TelemetryCapacityMaxDataLength() (4)
/*!
* Current state of the transmuter current control loop
*/
typedef struct
{
float pTerm;
float iTerm;
float dTerm;
float fTerm;
}Transmuter_TelemetryControlLoop_t;
//! Create the Transmuter_TelemetryControlLoop packet
void encodeTransmuter_TelemetryControlLoopPacketStructure(void* pkt, const Transmuter_TelemetryControlLoop_t* user);
//! Decode the Transmuter_TelemetryControlLoop packet
int decodeTransmuter_TelemetryControlLoopPacketStructure(const void* pkt, Transmuter_TelemetryControlLoop_t* user);
//! Create the Transmuter_TelemetryControlLoop packet from parameters
void encodeTransmuter_TelemetryControlLoopPacket(void* pkt, float pTerm, float iTerm, float dTerm, float fTerm);
//! Decode the Transmuter_TelemetryControlLoop packet to parameters
int decodeTransmuter_TelemetryControlLoopPacket(const void* pkt, float* pTerm, float* iTerm, float* dTerm, float* fTerm);
//! return the packet ID for the Transmuter_TelemetryControlLoop packet
#define getTransmuter_TelemetryControlLoopPacketID() (PKT_TRANSMUTER_TELEMETRY_CTRL_LOOP)
//! return the minimum encoded length for the Transmuter_TelemetryControlLoop packet
#define getTransmuter_TelemetryControlLoopMinDataLength() (8)
//! return the maximum encoded length for the Transmuter_TelemetryControlLoop packet
#define getTransmuter_TelemetryControlLoopMaxDataLength() (8)
/*!
* Power information for the Auxilary Power Board
*/
typedef struct
{
float apbVoltage; //!< APB output voltage (V)
float apbCurrent; //!< APB output current (A)
}Transmuter_TelemetryAPBPower_t;
//! Create the Transmuter_TelemetryAPBPower packet
void encodeTransmuter_TelemetryAPBPowerPacketStructure(void* pkt, const Transmuter_TelemetryAPBPower_t* user);
//! Decode the Transmuter_TelemetryAPBPower packet
int decodeTransmuter_TelemetryAPBPowerPacketStructure(const void* pkt, Transmuter_TelemetryAPBPower_t* user);
//! Create the Transmuter_TelemetryAPBPower packet from parameters
void encodeTransmuter_TelemetryAPBPowerPacket(void* pkt, float apbVoltage, float apbCurrent);
//! Decode the Transmuter_TelemetryAPBPower packet to parameters
int decodeTransmuter_TelemetryAPBPowerPacket(const void* pkt, float* apbVoltage, float* apbCurrent);
//! return the packet ID for the Transmuter_TelemetryAPBPower packet
#define getTransmuter_TelemetryAPBPowerPacketID() (PKT_TRANSMUTER_TELEMETRY_APB)
//! return the minimum encoded length for the Transmuter_TelemetryAPBPower packet
#define getTransmuter_TelemetryAPBPowerMinDataLength() (4)
//! return the maximum encoded length for the Transmuter_TelemetryAPBPower packet
#define getTransmuter_TelemetryAPBPowerMaxDataLength() (4)
// Initial and verify values for WarningLevels
#define Transmuter_WarningLevels_engineTemp_InitValue 140
#define Transmuter_WarningLevels_engineTemp_VerifyMin 50
/*!
* Warning level configuration values
*/
typedef struct
{
uint8_t engineTemp; //!< Engine (CHT) temperature warning level
}Transmuter_WarningLevels_t;
//! Set a Transmuter_WarningLevels_t to initial values
void initTransmuter_WarningLevels_t(Transmuter_WarningLevels_t* user);
//! Create the Transmuter_WarningLevels packet
void encodeTransmuter_WarningLevelsPacketStructure(void* pkt, const Transmuter_WarningLevels_t* user);
//! Decode the Transmuter_WarningLevels packet
int decodeTransmuter_WarningLevelsPacketStructure(const void* pkt, Transmuter_WarningLevels_t* user);
//! Create the Transmuter_WarningLevels packet from parameters
void encodeTransmuter_WarningLevelsPacket(void* pkt, uint8_t engineTemp);
//! Decode the Transmuter_WarningLevels packet to parameters
int decodeTransmuter_WarningLevelsPacket(const void* pkt, uint8_t* engineTemp);
//! Verify a Transmuter_WarningLevels_t has acceptable values
int verifyTransmuter_WarningLevels_t(Transmuter_WarningLevels_t* user);
//! return the packet ID for the Transmuter_WarningLevels packet
#define getTransmuter_WarningLevelsPacketID() (PKT_TRANSMUTER_WARNING_LEVELS)
//! return the minimum encoded length for the Transmuter_WarningLevels packet
#define getTransmuter_WarningLevelsMinDataLength() (1)
//! return the maximum encoded length for the Transmuter_WarningLevels packet
#define getTransmuter_WarningLevelsMaxDataLength() (1)
// Initial and verify values for EFISettings
#define Transmuter_EFISettings_ecuAddress_InitValue 200
#define Transmuter_EFISettings_ecuAddress_VerifyMax 254
#define Transmuter_EFISettings_triplexAddress_InitValue 201
#define Transmuter_EFISettings_triplexAddress_VerifyMax 254
#define Transmuter_EFISettings_fuelPressureMin_InitValue 5.0f
#define Transmuter_EFISettings_fuelPressureMin_VerifyMin 1.0f
#define Transmuter_EFISettings_fuelPressureMin_VerifyMax 25.0f
/*!
* ECU connection configuration packet
*/
typedef struct
{
uint8_t ecuAddress; //!< CAN Node ID for the ECU
uint16_t ecuFirmwareChecksum; //!< ECU firmware checksum
uint16_t ecuSettingsChecksum; //!< ECU settings checksum
uint8_t triplexAddress; //!< CAN Node ID for the triplex pump
uint16_t triplexFirmwareChecksum; //!< Triplex pump firmware checksum
float fuelPressureMin; //!< Minimum required fuel pressure
uint8_t pumpController; //!< Fuel pressure control method
}Transmuter_EFISettings_t;
//! Set a Transmuter_EFISettings_t to initial values
void initTransmuter_EFISettings_t(Transmuter_EFISettings_t* user);
//! Create the Transmuter_EFISettings packet
void encodeTransmuter_EFISettingsPacketStructure(void* pkt, const Transmuter_EFISettings_t* user);
//! Decode the Transmuter_EFISettings packet
int decodeTransmuter_EFISettingsPacketStructure(const void* pkt, Transmuter_EFISettings_t* user);
//! Create the Transmuter_EFISettings packet from parameters
void encodeTransmuter_EFISettingsPacket(void* pkt, uint8_t ecuAddress, uint16_t ecuFirmwareChecksum, uint16_t ecuSettingsChecksum, uint8_t triplexAddress, uint16_t triplexFirmwareChecksum, float fuelPressureMin, uint8_t pumpController);
//! Decode the Transmuter_EFISettings packet to parameters
int decodeTransmuter_EFISettingsPacket(const void* pkt, uint8_t* ecuAddress, uint16_t* ecuFirmwareChecksum, uint16_t* ecuSettingsChecksum, uint8_t* triplexAddress, uint16_t* triplexFirmwareChecksum, float* fuelPressureMin, uint8_t* pumpController);
//! Verify a Transmuter_EFISettings_t has acceptable values
int verifyTransmuter_EFISettings_t(Transmuter_EFISettings_t* user);
//! return the packet ID for the Transmuter_EFISettings packet
#define getTransmuter_EFISettingsPacketID() (PKT_TRANSMUTER_EFI_CONFIG)
//! return the minimum encoded length for the Transmuter_EFISettings packet
#define getTransmuter_EFISettingsMinDataLength() (10)
//! return the maximum encoded length for the Transmuter_EFISettings packet
#define getTransmuter_EFISettingsMaxDataLength() (11)
// Initial and verify values for GeneratorSettings
#define Transmuter_GeneratorSettings_beltRatio_InitValue 1.0f
#define Transmuter_GeneratorSettings_beltRatio_VerifyMin 0.1f
#define Transmuter_GeneratorSettings_beltRatio_VerifyMax 10.0f
#define Transmuter_GeneratorSettings_rpmThreshold_InitValue 350
#define Transmuter_GeneratorSettings_rpmThreshold_VerifyMax 5000
#define Transmuter_GeneratorSettings_powerLossTimeout_InitValue 25
/*!
* Generator motor parameters
*/
typedef struct
{
float beltRatio; //!< Belt ratio between engine and generator motor
uint16_t rpmThreshold; //!< Allowable RPM measurement difference between generator and engine
uint8_t powerLossTimeout; //!< Timeout before system disables due to engine power loss. Set to zero to disable timeout
}Transmuter_GeneratorSettings_t;
//! Set a Transmuter_GeneratorSettings_t to initial values
void initTransmuter_GeneratorSettings_t(Transmuter_GeneratorSettings_t* user);
//! Create the Transmuter_GeneratorSettings packet
void encodeTransmuter_GeneratorSettingsPacketStructure(void* pkt, const Transmuter_GeneratorSettings_t* user);
//! Decode the Transmuter_GeneratorSettings packet
int decodeTransmuter_GeneratorSettingsPacketStructure(const void* pkt, Transmuter_GeneratorSettings_t* user);
//! Create the Transmuter_GeneratorSettings packet from parameters
void encodeTransmuter_GeneratorSettingsPacket(void* pkt, float beltRatio, uint16_t rpmThreshold, uint8_t powerLossTimeout);
//! Decode the Transmuter_GeneratorSettings packet to parameters
int decodeTransmuter_GeneratorSettingsPacket(const void* pkt, float* beltRatio, uint16_t* rpmThreshold, uint8_t* powerLossTimeout);
//! Verify a Transmuter_GeneratorSettings_t has acceptable values
int verifyTransmuter_GeneratorSettings_t(Transmuter_GeneratorSettings_t* user);
//! return the packet ID for the Transmuter_GeneratorSettings packet
#define getTransmuter_GeneratorSettingsPacketID() (PKT_TRANSMUTER_GEN_CONFIG)
//! return the minimum encoded length for the Transmuter_GeneratorSettings packet
#define getTransmuter_GeneratorSettingsMinDataLength() (5)
//! return the maximum encoded length for the Transmuter_GeneratorSettings packet
#define getTransmuter_GeneratorSettingsMaxDataLength() (5)
// Initial and verify values for StartingSettings
#define Transmuter_StartingSettings_retries_InitValue 3
#define Transmuter_StartingSettings_retries_VerifyMax 50
#define Transmuter_StartingSettings_timeout_InitValue 50
#define Transmuter_StartingSettings_timeout_VerifyMin 1
#define Transmuter_StartingSettings_rpm_InitValue 3000
#define Transmuter_StartingSettings_rpm_VerifyMin 500
#define Transmuter_StartingSettings_rpm_VerifyMax 25000
#define Transmuter_StartingSettings_throttle_InitValue 25
#define Transmuter_StartingSettings_throttle_VerifyMax 100
#define Transmuter_StartingSettings_settlingPeriod_InitValue 25
#define Transmuter_StartingSettings_settlingPeriod_VerifyMin 10
#define Transmuter_StartingSettings_settlingPeriod_VerifyMax 250
/*!
* Engine starting settings
*/
typedef struct
{
uint8_t retries; //!< Number of auto-retries allowed for engine starting routine
uint8_t timeout; //!< Timeout for engine starting routine
uint16_t rpm; //!< Starting RPM value
uint8_t throttle; //!< Starting throttle position
uint8_t settlingPeriod; //!< Settling time after reaching starting RPM
}Transmuter_StartingSettings_t;
//! Set a Transmuter_StartingSettings_t to initial values
void initTransmuter_StartingSettings_t(Transmuter_StartingSettings_t* user);
//! Create the Transmuter_StartingSettings packet
void encodeTransmuter_StartingSettingsPacketStructure(void* pkt, const Transmuter_StartingSettings_t* user);
//! Decode the Transmuter_StartingSettings packet
int decodeTransmuter_StartingSettingsPacketStructure(const void* pkt, Transmuter_StartingSettings_t* user);
//! Create the Transmuter_StartingSettings packet from parameters
void encodeTransmuter_StartingSettingsPacket(void* pkt, uint8_t retries, uint8_t timeout, uint16_t rpm, uint8_t throttle, uint8_t settlingPeriod);
//! Decode the Transmuter_StartingSettings packet to parameters
int decodeTransmuter_StartingSettingsPacket(const void* pkt, uint8_t* retries, uint8_t* timeout, uint16_t* rpm, uint8_t* throttle, uint8_t* settlingPeriod);
//! Verify a Transmuter_StartingSettings_t has acceptable values
int verifyTransmuter_StartingSettings_t(Transmuter_StartingSettings_t* user);
//! return the packet ID for the Transmuter_StartingSettings packet
#define getTransmuter_StartingSettingsPacketID() (PKT_TRANSMUTER_STARTING_SETTINGS)
//! return the minimum encoded length for the Transmuter_StartingSettings packet
#define getTransmuter_StartingSettingsMinDataLength() (6)
//! return the maximum encoded length for the Transmuter_StartingSettings packet
#define getTransmuter_StartingSettingsMaxDataLength() (6)
// Initial and verify values for PowerMap
#define Transmuter_PowerMap_size_VerifyMin 2
#define Transmuter_PowerMap_size_VerifyMax 15
#define Transmuter_PowerMap_power_VerifyMin 0
#define Transmuter_PowerMap_power_VerifyMax 25000
#define Transmuter_PowerMap_rpm_VerifyMin 0
#define Transmuter_PowerMap_rpm_VerifyMax 25000
#define Transmuter_PowerMap_powerFilterHz_InitValue 1.0f
#define Transmuter_PowerMap_powerFilterHz_VerifyMin 0.01f
#define Transmuter_PowerMap_powerFilterHz_VerifyMax 50.0f
/*!
* Configuration of transmuter power map lookup table
*/
typedef struct
{
uint8_t size;
int16_t power[15]; //!< Power Input (W)
int16_t rpm[15]; //!< Speed Output (RPM)
float powerFilterHz; //!< Power demand low pass filter corner frequency
}Transmuter_PowerMap_t;
//! Set a Transmuter_PowerMap_t to initial values
void initTransmuter_PowerMap_t(Transmuter_PowerMap_t* user);
//! Create the Transmuter_PowerMap packet
void encodeTransmuter_PowerMapPacketStructure(void* pkt, const Transmuter_PowerMap_t* user);
//! Decode the Transmuter_PowerMap packet
int decodeTransmuter_PowerMapPacketStructure(const void* pkt, Transmuter_PowerMap_t* user);
//! Verify a Transmuter_PowerMap_t has acceptable values
int verifyTransmuter_PowerMap_t(Transmuter_PowerMap_t* user);
//! return the packet ID for the Transmuter_PowerMap packet
#define getTransmuter_PowerMapPacketID() (PKT_TRANSMUTER_POWER_MAP)
//! return the minimum encoded length for the Transmuter_PowerMap packet
#define getTransmuter_PowerMapMinDataLength() (1)
//! return the maximum encoded length for the Transmuter_PowerMap packet
#define getTransmuter_PowerMapMaxDataLength() (63)
// Initial and verify values for BatterySettings
#define Transmuter_BatterySettings_nominalVoltage_InitValue 48
#define Transmuter_BatterySettings_nominalVoltage_VerifyMin 20
#define Transmuter_BatterySettings_nominalVoltage_VerifyMax 100
#define Transmuter_BatterySettings_chargingCurrent_InitValue 5
#define Transmuter_BatterySettings_capacity_InitValue 5000
#define Transmuter_BatterySettings_currentScaler_InitValue 1.0f
#define Transmuter_BatterySettings_currentScaler_VerifyMin 0.75f
#define Transmuter_BatterySettings_currentScaler_VerifyMax 1.25f
#define Transmuter_BatterySettings_currentOffset_InitValue 0.0f
/*!
* Configuration of battery charging parameters
*/
typedef struct
{
float nominalVoltage;
float chargingCurrent;
uint16_t capacity; //!< Battery capacity
float currentScaler; //!< Battery current measurement scaler value
float currentOffset; //!< Battery current measurement offset value
}Transmuter_BatterySettings_t;
//! Set a Transmuter_BatterySettings_t to initial values
void initTransmuter_BatterySettings_t(Transmuter_BatterySettings_t* user);
//! Create the Transmuter_BatterySettings packet
void encodeTransmuter_BatterySettingsPacketStructure(void* pkt, const Transmuter_BatterySettings_t* user);
//! Decode the Transmuter_BatterySettings packet
int decodeTransmuter_BatterySettingsPacketStructure(const void* pkt, Transmuter_BatterySettings_t* user);
//! Create the Transmuter_BatterySettings packet from parameters
void encodeTransmuter_BatterySettingsPacket(void* pkt, float nominalVoltage, float chargingCurrent, uint16_t capacity, float currentScaler, float currentOffset);
//! Decode the Transmuter_BatterySettings packet to parameters
int decodeTransmuter_BatterySettingsPacket(const void* pkt, float* nominalVoltage, float* chargingCurrent, uint16_t* capacity, float* currentScaler, float* currentOffset);
//! Verify a Transmuter_BatterySettings_t has acceptable values
int verifyTransmuter_BatterySettings_t(Transmuter_BatterySettings_t* user);
//! return the packet ID for the Transmuter_BatterySettings packet
#define getTransmuter_BatterySettingsPacketID() (PKT_TRANSMUTER_BATTERY_SETTINGS)
//! return the minimum encoded length for the Transmuter_BatterySettings packet
#define getTransmuter_BatterySettingsMinDataLength() (7)
//! return the maximum encoded length for the Transmuter_BatterySettings packet
#define getTransmuter_BatterySettingsMaxDataLength() (11)
/*!
* Transmuter packet selection. Enable or disable various telemetry packets
*/
typedef struct
{
Transmuter_TelemetryPackets_t packets; //!< Telemetry packet selection
}Transmuter_TelemetrySettings_t;
//! Set a Transmuter_TelemetrySettings_t to initial values
void initTransmuter_TelemetrySettings_t(Transmuter_TelemetrySettings_t* user);
//! Create the Transmuter_TelemetrySettings packet
void encodeTransmuter_TelemetrySettingsPacketStructure(void* pkt, const Transmuter_TelemetrySettings_t* user);
//! Decode the Transmuter_TelemetrySettings packet
int decodeTransmuter_TelemetrySettingsPacketStructure(const void* pkt, Transmuter_TelemetrySettings_t* user);
//! Create the Transmuter_TelemetrySettings packet from parameters
void encodeTransmuter_TelemetrySettingsPacket(void* pkt, const Transmuter_TelemetryPackets_t* packets);
//! Decode the Transmuter_TelemetrySettings packet to parameters
int decodeTransmuter_TelemetrySettingsPacket(const void* pkt, Transmuter_TelemetryPackets_t* packets);
//! return the packet ID for the Transmuter_TelemetrySettings packet
#define getTransmuter_TelemetrySettingsPacketID() (PKT_TRANSMUTER_TELEMETRY_CONFIG)
//! return the minimum encoded length for the Transmuter_TelemetrySettings packet
#define getTransmuter_TelemetrySettingsMinDataLength() (1)
//! return the maximum encoded length for the Transmuter_TelemetrySettings packet
#define getTransmuter_TelemetrySettingsMaxDataLength() (1)
// Initial and verify values for ThrottleControlLoopSettings
#define Transmuter_ThrottleControlLoopSettings_Kp_InitValue 25
#define Transmuter_ThrottleControlLoopSettings_Kp_VerifyMin 0.0f
#define Transmuter_ThrottleControlLoopSettings_Kp_VerifyMax 50.0f
#define Transmuter_ThrottleControlLoopSettings_Ki_InitValue 2.5
#define Transmuter_ThrottleControlLoopSettings_Ki_VerifyMin 0.0f
#define Transmuter_ThrottleControlLoopSettings_Ki_VerifyMax 50.0f
#define Transmuter_ThrottleControlLoopSettings_Kd_InitValue 0
#define Transmuter_ThrottleControlLoopSettings_Kd_VerifyMin 0.0f
#define Transmuter_ThrottleControlLoopSettings_Kd_VerifyMax 50.0f
#define Transmuter_ThrottleControlLoopSettings_Kf_InitValue 0
#define Transmuter_ThrottleControlLoopSettings_Kf_VerifyMin 0.0f
#define Transmuter_ThrottleControlLoopSettings_Kf_VerifyMax 50.0f
#define Transmuter_ThrottleControlLoopSettings_throttleMin_InitValue 10
#define Transmuter_ThrottleControlLoopSettings_throttleMin_VerifyMax 100
#define Transmuter_ThrottleControlLoopSettings_throttleMax_InitValue 100
#define Transmuter_ThrottleControlLoopSettings_throttleMax_VerifyMax 100
#define Transmuter_ThrottleControlLoopSettings_slewLimit_InitValue 100
#define Transmuter_ThrottleControlLoopSettings_slewLimit_VerifyMin 10
#define Transmuter_ThrottleControlLoopSettings_slewLimit_VerifyMax 1000
#define Transmuter_ThrottleControlLoopSettings_throttleFilterHz_InitValue 1.0f
#define Transmuter_ThrottleControlLoopSettings_throttleFilterHz_VerifyMin 0.01f
#define Transmuter_ThrottleControlLoopSettings_throttleFilterHz_VerifyMax 50.0f
/*!
* Engine throttle control loop settings
*/
typedef struct
{
float Kp;
float Ki;
float Kd;
float Kf;
uint8_t throttleMin; //!< Minimum engine throttle position
uint8_t throttleMax; //!< Maximum engine throttle position
uint16_t slewLimit; //!< Maximum throttle slew rate
float throttleFilterHz; //!< Throttle command low pass filter corner frequency
}Transmuter_ThrottleControlLoopSettings_t;
//! Set a Transmuter_ThrottleControlLoopSettings_t to initial values
void initTransmuter_ThrottleControlLoopSettings_t(Transmuter_ThrottleControlLoopSettings_t* user);
//! Create the Transmuter_ThrottleControlLoopSettings packet
void encodeTransmuter_ThrottleControlLoopSettingsPacketStructure(void* pkt, const Transmuter_ThrottleControlLoopSettings_t* user);
//! Decode the Transmuter_ThrottleControlLoopSettings packet
int decodeTransmuter_ThrottleControlLoopSettingsPacketStructure(const void* pkt, Transmuter_ThrottleControlLoopSettings_t* user);
//! Verify a Transmuter_ThrottleControlLoopSettings_t has acceptable values
int verifyTransmuter_ThrottleControlLoopSettings_t(Transmuter_ThrottleControlLoopSettings_t* user);
//! return the packet ID for the Transmuter_ThrottleControlLoopSettings packet
#define getTransmuter_ThrottleControlLoopSettingsPacketID() (PKT_TRANSMUTER_CTRL_LOOP_SETTINGS)
//! return the minimum encoded length for the Transmuter_ThrottleControlLoopSettings packet
#define getTransmuter_ThrottleControlLoopSettingsMinDataLength() (12)
//! return the maximum encoded length for the Transmuter_ThrottleControlLoopSettings packet
#define getTransmuter_ThrottleControlLoopSettingsMaxDataLength() (14)
#ifdef __cplusplus
}
#endif
#endif // _TRANSMUTERPACKETS_H