mirror of https://github.com/ArduPilot/ardupilot
178 lines
7.5 KiB
C
178 lines
7.5 KiB
C
|
// TransmuterProtocol.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 _TRANSMUTERPROTOCOL_H
|
||
|
#define _TRANSMUTERPROTOCOL_H
|
||
|
|
||
|
// Language target is C, C++ compilers: don't mangle us
|
||
|
#ifdef __cplusplus
|
||
|
extern "C" {
|
||
|
#endif
|
||
|
|
||
|
/*!
|
||
|
* \file
|
||
|
* \mainpage Transmuter protocol stack
|
||
|
*
|
||
|
* This is the ICD for the Currawong Engineering Hybrid Transmuter. This
|
||
|
* document details the Transmuter command and packet structure for
|
||
|
* communication with and configuration of the Transmuter.
|
||
|
*
|
||
|
* 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: 15
|
||
|
*
|
||
|
* The protocol version is 0.11
|
||
|
*/
|
||
|
|
||
|
#include <stdint.h>
|
||
|
#include <stdbool.h>
|
||
|
|
||
|
//! \return the protocol API enumeration
|
||
|
#define getTransmuterApi() 15
|
||
|
|
||
|
//! \return the protocol version string
|
||
|
#define getTransmuterVersion() "0.11"
|
||
|
|
||
|
/*!
|
||
|
* Defines the various high-level operational modes of the Transmuter state
|
||
|
* machine
|
||
|
*/
|
||
|
typedef enum
|
||
|
{
|
||
|
TRANSMUTER_MODE_STARTUP = 0, //!< Initial powerup mode of the transmuter
|
||
|
TRANSMUTER_MODE_STANDBY, //!< Transmuter is in standby mode
|
||
|
TRANSMUTER_MODE_PREFLIGHT, //!< Transmuter is in preflight check mode
|
||
|
TRANSMUTER_MODE_STARTING, //!< Transmuter is attempting to start the engine
|
||
|
TRANSMUTER_MODE_WARMUP, //!< Transmuter is in warmup mode
|
||
|
TRANSMUTER_MODE_RPM, //!< Transmuter is running in RPM control mode
|
||
|
TRANSMUTER_MODE_CURRENT, //!< Transmuter is running in CURRENT control mode
|
||
|
TRANSMUTER_MODE_PWM, //!< Transmuter is running in PWM control mode
|
||
|
TRANSMUTER_MODE_NUM_MODES //!< Number of transmuter operational modes
|
||
|
} TransmuterModes;
|
||
|
|
||
|
//! \return the label of a 'TransmuterModes' enum entry, based on its value
|
||
|
const char* TransmuterModes_EnumLabel(int value);
|
||
|
|
||
|
//! \return the title of a 'TransmuterModes' enum entry, based on its value
|
||
|
const char* TransmuterModes_EnumTitle(int value);
|
||
|
|
||
|
/*!
|
||
|
* Defines the various states of the transmuter engine starting state machine
|
||
|
*/
|
||
|
typedef enum
|
||
|
{
|
||
|
TRANSMUTER_START_INIT = 0, //!< Initializing the starting routine
|
||
|
TRANSMUTER_START_PRIMING, //!< Priming engine / fuel pump / etc
|
||
|
TRANSMUTER_START_DISABLE_ECU, //!< Disabling ECU prior to engine cranking
|
||
|
TRANSMUTER_START_CRANK_GEN, //!< Spinning the generator
|
||
|
TRANSMUTER_START_ENABLE_ECU, //!< Enable ECU once the system is spinning
|
||
|
TRANSMUTER_START_FAILURE = 0x0F //!< Starting failed
|
||
|
} TransmuterStartingStates;
|
||
|
|
||
|
//! \return the label of a 'TransmuterStartingStates' enum entry, based on its value
|
||
|
const char* TransmuterStartingStates_EnumLabel(int value);
|
||
|
|
||
|
//! \return the title of a 'TransmuterStartingStates' enum entry, based on its value
|
||
|
const char* TransmuterStartingStates_EnumTitle(int value);
|
||
|
|
||
|
/*!
|
||
|
* Possible transmuter system standby causes
|
||
|
*/
|
||
|
typedef enum
|
||
|
{
|
||
|
TRANSMUTER_STANDBY_CAUSE_POWERUP = 0x01, //!< System power-on (or reset)
|
||
|
TRANSMUTER_STANDBY_CAUSE_HW_DISABLE = 0x10, //!< System standby caused by hardware inhibit line
|
||
|
TRANSMUTER_STANDBY_CAUSE_SW_DISABLE, //!< System standby casued by software inhibit
|
||
|
TRANSMUTER_STANDBY_CAUSE_STARTING_RETRIES = 0x20, //!< Too many starting attempts
|
||
|
TRANSMUTER_STANDBY_CAUSE_CMD = 0x30, //!< Standby due to received command
|
||
|
TRANSMUTER_STANDBY_CAUSE_CRITICAL_RUNNING_ERROR = 0x40, //!< Standby due to critical error during running
|
||
|
TRANSMUTER_STANDBY_CAUSE_UNKNOWN_MODE = 0x80 //!< Unknown operational mode
|
||
|
} TransmuterStandbyCause;
|
||
|
|
||
|
//! \return the label of a 'TransmuterStandbyCause' enum entry, based on its value
|
||
|
const char* TransmuterStandbyCause_EnumLabel(int value);
|
||
|
|
||
|
/*!
|
||
|
* Fuel pump mode
|
||
|
*/
|
||
|
typedef enum
|
||
|
{
|
||
|
TRANSMUTER_PUMP_TRIPLEX = 0x00, //!< Fuel pressure is regulated via triplex pump
|
||
|
TRANSMUTER_PUMP_ECU = 0x01 //!< Fuel pressure is regulated via ECU
|
||
|
} TransmuterFuelPumpMode;
|
||
|
|
||
|
//! \return the label of a 'TransmuterFuelPumpMode' enum entry, based on its value
|
||
|
const char* TransmuterFuelPumpMode_EnumLabel(int value);
|
||
|
|
||
|
/*!
|
||
|
* Transmuter packet ID values
|
||
|
*/
|
||
|
typedef enum
|
||
|
{
|
||
|
PKT_TRANSMUTER_STANDBY = 0x10, //!< Command the transmuter to enter standby mode
|
||
|
PKT_TRANSMUTER_PREFLIGHT = 0x11, //!< Command the transmuter to enter preflight mode
|
||
|
PKT_TRANSMUTER_WARMUP = 0x12, //!< Command the transmuter to enter engine warmup mode
|
||
|
PKT_TRANSMUTER_RUN = 0x15, //!< Command the transmuter to enter running mode
|
||
|
PKT_TRANSMUTER_PWM = 0x20, //!< Command the transmuter to enter PWM mode
|
||
|
PKT_TRANSMUTER_SYSTEM_CMD = 0x50, //!< Send various system commands to the transmuter
|
||
|
PKT_TRANSMUTER_TELEMETRY_STATUS = 0x80, //!< General transmuter status information
|
||
|
PKT_TRANSMUTER_TELEMETRY_POWER = 0x81, //!< Current and power information
|
||
|
PKT_TRANSMUTER_TELEMETRY_SETPOINT = 0x82, //!< System setpoint information
|
||
|
PKT_TRANSMUTER_TELEMETRY_GEN = 0x83, //!< Generator and EFI status information
|
||
|
PKT_TRANSMUTER_TELEMETRY_CAPACITY = 0x84, //!< System capacity information
|
||
|
PKT_TRANSMUTER_TELEMETRY_CTRL_LOOP = 0x86, //!< Control loop output information
|
||
|
PKT_TRANSMUTER_TELEMETRY_APB = 0x87, //!< Power output from auxillary power board
|
||
|
PKT_TRANSMUTER_TELEMETRY_CONFIG = 0x94, //!< Telemetry settings
|
||
|
PKT_TRANSMUTER_WARNING_LEVELS = 0x95, //!< Warning threshold calibration
|
||
|
PKT_TRANSMUTER_CTRL_LOOP_SETTINGS = 0xA0, //!< Control loop settings packet
|
||
|
PKT_TRANSMUTER_BATTERY_SETTINGS = 0xB0, //!< Battery management configuration
|
||
|
PKT_TRANSMUTER_EFI_CONFIG = 0xB5, //!< EFI configuration
|
||
|
PKT_TRANSMUTER_GEN_CONFIG = 0xB6, //!< Generator motor config
|
||
|
PKT_TRANSMUTER_POWER_MAP = 0xC0, //!< Engine power map
|
||
|
PKT_TRANSMUTER_STARTING_SETTINGS = 0xCA, //!< Engine starting settings
|
||
|
PKT_TRANSMUTER_BULK_TRANSFER = 0xF0 //!< Bulk data transfer (long packets)
|
||
|
} TransmuterPackets;
|
||
|
|
||
|
//! \return the label of a 'TransmuterPackets' enum entry, based on its value
|
||
|
const char* TransmuterPackets_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* getTransmuterPacketData(void* pkt);
|
||
|
|
||
|
//! \return the packet data pointer from the packet, const
|
||
|
const uint8_t* getTransmuterPacketDataConst(const void* pkt);
|
||
|
|
||
|
//! Complete a packet after the data have been encoded
|
||
|
void finishTransmuterPacket(void* pkt, int size, uint32_t packetID);
|
||
|
|
||
|
//! \return the size of a packet from the packet header
|
||
|
int getTransmuterPacketSize(const void* pkt);
|
||
|
|
||
|
//! \return the ID of a packet from the packet header
|
||
|
uint32_t getTransmuterPacketID(const void* pkt);
|
||
|
|
||
|
#ifdef __cplusplus
|
||
|
}
|
||
|
#endif
|
||
|
#endif // _TRANSMUTERPROTOCOL_H
|