ardupilot/libraries/AP_PiccoloCAN/piccolo_protocol/TransmuterDefines.h

161 lines
6.6 KiB
C

// TransmuterDefines.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 _TRANSMUTERDEFINES_H
#define _TRANSMUTERDEFINES_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"
/*!
* Transmuter operational status information
*/
typedef struct
{
uint8_t mode; //!< Transmuter operational mode
bool hwEnable; //!< Hardware enable is active
bool swEnable; //!< Software enable is active
bool anyErrors; //!< Critical error flag set (refer to error status packet)
bool anyWarnings; //!< Warning flag set (refer to error status packet)
bool manualCurrent; //!< 0 = Auto current, 1 = Manual current
bool manualSpeed; //!< 0 = Auto RPM, 1 = Manual RPM
bool efiEnabled; //!< EFI system enabled status
bool readyToRun; //!< Transmuter is ready to run
}Transmuter_StatusBits_t;
//! return the minimum encoded length for the Transmuter_StatusBits_t structure
#define getMinLengthOfTransmuter_StatusBits_t() (2)
//! return the maximum encoded length for the Transmuter_StatusBits_t structure
#define getMaxLengthOfTransmuter_StatusBits_t() (2)
//! Encode a Transmuter_StatusBits_t into a byte array
void encodeTransmuter_StatusBits_t(uint8_t* data, int* bytecount, const Transmuter_StatusBits_t* user);
//! Decode a Transmuter_StatusBits_t from a byte array
int decodeTransmuter_StatusBits_t(const uint8_t* data, int* bytecount, Transmuter_StatusBits_t* user);
/*!
* Transmuter operational status warning bits
*/
typedef struct
{
bool motor; //!< General motor control warning (refer to the motor warnings packet)
bool batVoltage; //!< Battery voltage is outside configured range
bool batCurrent; //!< Battery current is outside configured range
bool genCurrent; //!< Generator current is outside configured range
bool genTemp; //!< Generator motor temperature exceeds warning limit
bool escTemp; //!< ESC MOSFET temperature exceeds warning limit
bool ecu; //!< General ECU warning
bool pump; //!< General fuel pump warning
bool rpmMismatch; //!< Mismatch between engine and generator RPM
bool powerLoss; //!< Engine is not generating expected power
bool engineLimit; //!< Engine is performing at maximum power limit
bool fuelPressure; //!< Fuel pressure warning
bool chtTemp; //!< Engine temperature exceeds warning threshold
}Transmuter_WarningBits_t;
//! return the minimum encoded length for the Transmuter_WarningBits_t structure
#define getMinLengthOfTransmuter_WarningBits_t() (3)
//! return the maximum encoded length for the Transmuter_WarningBits_t structure
#define getMaxLengthOfTransmuter_WarningBits_t() (3)
//! Encode a Transmuter_WarningBits_t into a byte array
void encodeTransmuter_WarningBits_t(uint8_t* data, int* bytecount, const Transmuter_WarningBits_t* user);
//! Decode a Transmuter_WarningBits_t from a byte array
int decodeTransmuter_WarningBits_t(const uint8_t* data, int* bytecount, Transmuter_WarningBits_t* user);
/*!
* Transmuter operational status error bits
*/
typedef struct
{
bool motor; //!< General motor control error (refer to the motor errors packet)
bool powerMap; //!< System power map is improperly configured
bool starting; //!< Error during starting routine
bool ecuConnection; //!< ECU connection lost
bool pumpConnection; //!< Fuel pump connection lost
bool rpmMismatch; //!< Engine stopped due to between engine and generator RPM
bool powerLoss; //!< Engine stopped due to not generating power
}Transmuter_ErrorBits_t;
//! return the minimum encoded length for the Transmuter_ErrorBits_t structure
#define getMinLengthOfTransmuter_ErrorBits_t() (3)
//! return the maximum encoded length for the Transmuter_ErrorBits_t structure
#define getMaxLengthOfTransmuter_ErrorBits_t() (3)
//! Encode a Transmuter_ErrorBits_t into a byte array
void encodeTransmuter_ErrorBits_t(uint8_t* data, int* bytecount, const Transmuter_ErrorBits_t* user);
//! Decode a Transmuter_ErrorBits_t from a byte array
int decodeTransmuter_ErrorBits_t(const uint8_t* data, int* bytecount, Transmuter_ErrorBits_t* user);
// Initial and verify values for TelemetryPackets
#define Transmuter_TelemetryPackets_status_InitValue 1
#define Transmuter_TelemetryPackets_power_InitValue 1
#define Transmuter_TelemetryPackets_setpoint_InitValue 1
#define Transmuter_TelemetryPackets_generator_InitValue 1
#define Transmuter_TelemetryPackets_capacity_InitValue 1
#define Transmuter_TelemetryPackets_ctrlLoop_InitValue 0
#define Transmuter_TelemetryPackets_apb_InitValue 0
typedef struct
{
bool status; //!< Enable TelemetryStatus packet
bool power; //!< Enable TelemetryPower packet
bool setpoint; //!< Enable TelemetrySetpoint packet
bool generator; //!< Enable TelemetryGenerator packet
bool capacity; //!< Enable TelemetryCapacity packet
bool ctrlLoop; //!< Enable ControlLoop packet
bool apb; //!< Enable TelemetryAPB packet
}Transmuter_TelemetryPackets_t;
//! return the minimum encoded length for the Transmuter_TelemetryPackets_t structure
#define getMinLengthOfTransmuter_TelemetryPackets_t() (1)
//! return the maximum encoded length for the Transmuter_TelemetryPackets_t structure
#define getMaxLengthOfTransmuter_TelemetryPackets_t() (1)
//! Set a Transmuter_TelemetryPackets_t to initial values
void initTransmuter_TelemetryPackets_t(Transmuter_TelemetryPackets_t* user);
//! Encode a Transmuter_TelemetryPackets_t into a byte array
void encodeTransmuter_TelemetryPackets_t(uint8_t* data, int* bytecount, const Transmuter_TelemetryPackets_t* user);
//! Decode a Transmuter_TelemetryPackets_t from a byte array
int decodeTransmuter_TelemetryPackets_t(const uint8_t* data, int* bytecount, Transmuter_TelemetryPackets_t* user);
#ifdef __cplusplus
}
#endif
#endif // _TRANSMUTERDEFINES_H