mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
unify typedef struct name_s {} name_t;
naming convention
This commit is contained in:
parent
1613c2d572
commit
8f3d9fae9a
18 changed files with 36 additions and 38 deletions
|
@ -111,7 +111,7 @@ static const char* const blackboxFieldHeaderNames[] = {
|
|||
};
|
||||
|
||||
/* All field definition structs should look like this (but with longer arrs): */
|
||||
typedef struct blackboxFieldDefinition_t {
|
||||
typedef struct blackboxFieldDefinition_s {
|
||||
const char *name;
|
||||
// If the field name has a number to be included in square brackets [1] afterwards, set it here, or -1 for no brackets:
|
||||
int8_t fieldNameIndex;
|
||||
|
@ -124,7 +124,7 @@ typedef struct blackboxFieldDefinition_t {
|
|||
#define BLACKBOX_SIMPLE_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
|
||||
#define BLACKBOX_CONDITIONAL_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
|
||||
|
||||
typedef struct blackboxSimpleFieldDefinition_t {
|
||||
typedef struct blackboxSimpleFieldDefinition_s {
|
||||
const char *name;
|
||||
int8_t fieldNameIndex;
|
||||
|
||||
|
@ -133,7 +133,7 @@ typedef struct blackboxSimpleFieldDefinition_t {
|
|||
uint8_t encode;
|
||||
} blackboxSimpleFieldDefinition_t;
|
||||
|
||||
typedef struct blackboxConditionalFieldDefinition_t {
|
||||
typedef struct blackboxConditionalFieldDefinition_s {
|
||||
const char *name;
|
||||
int8_t fieldNameIndex;
|
||||
|
||||
|
@ -143,7 +143,7 @@ typedef struct blackboxConditionalFieldDefinition_t {
|
|||
uint8_t condition; // Decide whether this field should appear in the log
|
||||
} blackboxConditionalFieldDefinition_t;
|
||||
|
||||
typedef struct blackboxDeltaFieldDefinition_t {
|
||||
typedef struct blackboxDeltaFieldDefinition_s {
|
||||
const char *name;
|
||||
int8_t fieldNameIndex;
|
||||
|
||||
|
@ -264,7 +264,7 @@ typedef enum BlackboxState {
|
|||
BLACKBOX_STATE_SHUTTING_DOWN
|
||||
} BlackboxState;
|
||||
|
||||
typedef struct blackboxMainState_t {
|
||||
typedef struct blackboxMainState_s {
|
||||
uint32_t time;
|
||||
|
||||
int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
|
||||
|
@ -290,13 +290,13 @@ typedef struct blackboxMainState_t {
|
|||
uint16_t rssi;
|
||||
} blackboxMainState_t;
|
||||
|
||||
typedef struct blackboxGpsState_t {
|
||||
typedef struct blackboxGpsState_s {
|
||||
int32_t GPS_home[2], GPS_coord[2];
|
||||
uint8_t GPS_numSat;
|
||||
} blackboxGpsState_t;
|
||||
|
||||
// This data is updated really infrequently:
|
||||
typedef struct blackboxSlowState_t {
|
||||
typedef struct blackboxSlowState_s {
|
||||
uint16_t flightModeFlags;
|
||||
uint8_t stateFlags;
|
||||
uint8_t failsafePhase;
|
||||
|
|
|
@ -109,40 +109,38 @@ typedef enum FlightLogEvent {
|
|||
FLIGHT_LOG_EVENT_LOG_END = 255
|
||||
} FlightLogEvent;
|
||||
|
||||
typedef struct flightLogEvent_syncBeep_t {
|
||||
typedef struct flightLogEvent_syncBeep_s {
|
||||
uint32_t time;
|
||||
} flightLogEvent_syncBeep_t;
|
||||
|
||||
typedef struct flightLogEvent_inflightAdjustment_t {
|
||||
typedef struct flightLogEvent_inflightAdjustment_s {
|
||||
uint8_t adjustmentFunction;
|
||||
bool floatFlag;
|
||||
int32_t newValue;
|
||||
float newFloatValue;
|
||||
} flightLogEvent_inflightAdjustment_t;
|
||||
|
||||
typedef struct flightLogEvent_loggingResume_t {
|
||||
typedef struct flightLogEvent_loggingResume_s {
|
||||
uint32_t logIteration;
|
||||
uint32_t currentTime;
|
||||
} flightLogEvent_loggingResume_t;
|
||||
|
||||
#define FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG 128
|
||||
|
||||
typedef struct flightLogEvent_gtuneCycleResult_t {
|
||||
typedef struct flightLogEvent_gtuneCycleResult_s {
|
||||
uint8_t gtuneAxis;
|
||||
int32_t gtuneGyroAVG;
|
||||
int16_t gtuneNewP;
|
||||
} flightLogEvent_gtuneCycleResult_t;
|
||||
|
||||
typedef union flightLogEventData_t
|
||||
{
|
||||
typedef union flightLogEventData_u {
|
||||
flightLogEvent_syncBeep_t syncBeep;
|
||||
flightLogEvent_inflightAdjustment_t inflightAdjustment;
|
||||
flightLogEvent_loggingResume_t loggingResume;
|
||||
flightLogEvent_gtuneCycleResult_t gtuneCycleResult;
|
||||
} flightLogEventData_t;
|
||||
|
||||
typedef struct flightLogEvent_t
|
||||
{
|
||||
typedef struct flightLogEvent_s {
|
||||
FlightLogEvent event;
|
||||
flightLogEventData_t data;
|
||||
} flightLogEvent_t;
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
#define MAX(a, b) ((a) > (b) ? (a) : (b))
|
||||
#define ABS(x) ((x) > 0 ? (x) : -(x))
|
||||
|
||||
typedef struct stdev_t
|
||||
typedef struct stdev_s
|
||||
{
|
||||
float m_oldM, m_newM, m_oldS, m_newS;
|
||||
int m_n;
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
typedef struct drv_adxl345_config_t {
|
||||
typedef struct drv_adxl345_config_s {
|
||||
bool useFifo;
|
||||
uint16_t dataRate;
|
||||
} drv_adxl345_config_t;
|
||||
|
|
|
@ -27,14 +27,14 @@ typedef enum {
|
|||
|
||||
#define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1)
|
||||
|
||||
typedef struct adc_config_t {
|
||||
typedef struct adc_config_s {
|
||||
uint8_t adcChannel; // ADC1_INxx channel number
|
||||
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
|
||||
bool enabled;
|
||||
uint8_t sampleTime;
|
||||
} adc_config_t;
|
||||
|
||||
typedef struct drv_adc_config_t {
|
||||
typedef struct drv_adc_config_s {
|
||||
bool enableVBat;
|
||||
bool enableRSSI;
|
||||
bool enableCurrentMeter;
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
typedef void (*baroOpFuncPtr)(void); // baro start operation
|
||||
typedef void (*baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
|
||||
|
||||
typedef struct baro_t {
|
||||
typedef struct baro_s {
|
||||
uint16_t ut_delay;
|
||||
uint16_t up_delay;
|
||||
baroOpFuncPtr start_ut;
|
||||
|
|
|
@ -72,7 +72,7 @@
|
|||
#define T_SETUP_PRESSURE_MAX (10)
|
||||
// 10/16 = 0.625 ms
|
||||
|
||||
typedef struct bmp280_calib_param_t {
|
||||
typedef struct bmp280_calib_param_s {
|
||||
uint16_t dig_T1; /* calibration T1 data */
|
||||
int16_t dig_T2; /* calibration T2 data */
|
||||
int16_t dig_T3; /* calibration T3 data */
|
||||
|
|
|
@ -42,7 +42,7 @@ static void i2c_er_handler(void);
|
|||
static void i2c_ev_handler(void);
|
||||
static void i2cUnstick(void);
|
||||
|
||||
typedef struct i2cDevice_t {
|
||||
typedef struct i2cDevice_s {
|
||||
I2C_TypeDef *dev;
|
||||
GPIO_TypeDef *gpio;
|
||||
uint16_t scl;
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
typedef struct flashGeometry_t {
|
||||
typedef struct flashGeometry_s {
|
||||
uint16_t sectors; // Count of the number of erasable blocks on the device
|
||||
|
||||
uint16_t pagesPerSector;
|
||||
|
|
|
@ -44,7 +44,7 @@ typedef struct sonarGPIOConfig_s {
|
|||
uint16_t echoPin;
|
||||
} sonarGPIOConfig_t;
|
||||
|
||||
typedef struct drv_pwm_config_t {
|
||||
typedef struct drv_pwm_config_s {
|
||||
bool useParallelPWM;
|
||||
bool usePPM;
|
||||
bool useSerialRx;
|
||||
|
|
|
@ -83,7 +83,7 @@ static uint8_t ppmFrameCount = 0;
|
|||
static uint8_t lastPPMFrameCount = 0;
|
||||
static uint8_t ppmCountShift = 0;
|
||||
|
||||
typedef struct ppmDevice {
|
||||
typedef struct ppmDevice_s {
|
||||
uint8_t pulseIndex;
|
||||
uint32_t previousTime;
|
||||
uint32_t currentTime;
|
||||
|
|
|
@ -36,7 +36,7 @@ typedef enum portOptions_t {
|
|||
|
||||
typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
|
||||
|
||||
typedef struct serialPort {
|
||||
typedef struct serialPort_s {
|
||||
|
||||
const struct serialPortVTable *vTable;
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#define LOWPASS_NUM_COEF 3
|
||||
#define LPF_ROUND(x) (x < 0 ? (x - 0.5f) : (x + 0.5f))
|
||||
|
||||
typedef struct lowpass_t {
|
||||
typedef struct lowpass_s {
|
||||
bool init;
|
||||
int16_t freq; // Normalized freq in 1/1000ths
|
||||
float bf[LOWPASS_NUM_COEF];
|
||||
|
|
|
@ -54,7 +54,7 @@ typedef enum mixerMode
|
|||
} mixerMode_e;
|
||||
|
||||
// Custom mixer data per motor
|
||||
typedef struct motorMixer_t {
|
||||
typedef struct motorMixer_s {
|
||||
float throttle;
|
||||
float roll;
|
||||
float pitch;
|
||||
|
@ -62,7 +62,7 @@ typedef struct motorMixer_t {
|
|||
} motorMixer_t;
|
||||
|
||||
// Custom mixer configuration
|
||||
typedef struct mixer_t {
|
||||
typedef struct mixer_s {
|
||||
uint8_t motorCount;
|
||||
uint8_t useServo;
|
||||
const motorMixer_t *motor;
|
||||
|
@ -86,7 +86,7 @@ typedef struct flight3DConfig_s {
|
|||
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
|
||||
} flight3DConfig_t;
|
||||
|
||||
typedef struct airplaneConfig_t {
|
||||
typedef struct airplaneConfig_s {
|
||||
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
||||
} airplaneConfig_t;
|
||||
|
||||
|
@ -150,7 +150,7 @@ typedef enum {
|
|||
#define SERVO_FLAPPERONS_MIN SERVO_FLAPPERON_1
|
||||
#define SERVO_FLAPPERONS_MAX SERVO_FLAPPERON_2
|
||||
|
||||
typedef struct servoMixer_t {
|
||||
typedef struct servoMixer_s {
|
||||
uint8_t targetChannel; // servo that receives the output of the rule
|
||||
uint8_t inputSource; // input channel for this rule
|
||||
int8_t rate; // range [-125;+125] ; can be used to adjust a rate 0-125% and a direction
|
||||
|
@ -165,12 +165,12 @@ typedef struct servoMixer_t {
|
|||
#define MAX_SERVO_BOXES 3
|
||||
|
||||
// Custom mixer configuration
|
||||
typedef struct mixerRules_t {
|
||||
typedef struct mixerRules_s {
|
||||
uint8_t servoRuleCount;
|
||||
const servoMixer_t *rule;
|
||||
} mixerRules_t;
|
||||
|
||||
typedef struct servoParam_t {
|
||||
typedef struct servoParam_s {
|
||||
int16_t min; // servo min
|
||||
int16_t max; // servo max
|
||||
int16_t middle; // servo middle
|
||||
|
|
|
@ -99,7 +99,7 @@ static gpsConfig_t *gpsConfig;
|
|||
static serialConfig_t *serialConfig;
|
||||
static serialPort_t *gpsPort;
|
||||
|
||||
typedef struct gpsInitData_t {
|
||||
typedef struct gpsInitData_s {
|
||||
uint8_t index;
|
||||
uint8_t baudrateIndex; // see baudRate_e
|
||||
const char *ubx;
|
||||
|
|
|
@ -81,7 +81,7 @@ typedef enum {
|
|||
|
||||
#define GPS_MESSAGE_STATE_ENTRY_COUNT (GPS_MESSAGE_STATE_MAX + 1)
|
||||
|
||||
typedef struct gpsData_t {
|
||||
typedef struct gpsData_s {
|
||||
uint8_t state; // GPS thread state. Used for detecting cable disconnects and configuring attached devices
|
||||
uint8_t baudrateIndex; // index into auto-detecting or current baudrate
|
||||
uint32_t errors; // gps error counter - crc error/lost of data/sync etc..
|
||||
|
|
|
@ -22,7 +22,7 @@ extern "C" {
|
|||
extern uint32_t bmp280_up;
|
||||
extern uint32_t bmp280_ut;
|
||||
|
||||
typedef struct bmp280_calib_param_t {
|
||||
typedef struct bmp280_calib_param_s {
|
||||
uint16_t dig_T1; /* calibration T1 data */
|
||||
int16_t dig_T2; /* calibration T2 data */
|
||||
int16_t dig_T3; /* calibration T3 data */
|
||||
|
|
|
@ -23,12 +23,12 @@ extern "C" {
|
|||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
typedef struct zigzagEncodingExpectation_t {
|
||||
typedef struct zigzagEncodingExpectation_s {
|
||||
int32_t input;
|
||||
uint32_t expected;
|
||||
} zigzagEncodingExpectation_t;
|
||||
|
||||
typedef struct floatToIntEncodingExpectation_t {
|
||||
typedef struct floatToIntEncodingExpectation_s {
|
||||
float input;
|
||||
uint32_t expected;
|
||||
} floatToIntEncodingExpectation_t;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue