Used forward declarations to remove #includes from header files
This commit is contained in:
parent
3999fbc95b
commit
0de27cf7c2
|
@ -72,6 +72,7 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
|
|
@ -53,6 +53,7 @@
|
|||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
|
|
@ -102,13 +102,10 @@ For further details see source code.
|
|||
regs Kusti, 23.10.2004
|
||||
*/
|
||||
|
||||
#ifndef __TFP_PRINTF__
|
||||
#define __TFP_PRINTF__
|
||||
#pragma once
|
||||
|
||||
#include <stdarg.h>
|
||||
|
||||
#include "drivers/serial.h"
|
||||
|
||||
void init_printf(void *putp, void (*putf) (void *, char));
|
||||
|
||||
int tfp_printf(const char *fmt, ...);
|
||||
|
@ -119,8 +116,6 @@ int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list
|
|||
#define printf tfp_printf
|
||||
#define sprintf tfp_sprintf
|
||||
|
||||
void setPrintfSerialPort(serialPort_t *serialPort);
|
||||
struct serialPort_s;
|
||||
void setPrintfSerialPort(struct serialPort_s *serialPort);
|
||||
void printfSupportInit(void);
|
||||
|
||||
|
||||
#endif
|
||||
|
|
|
@ -15,19 +15,21 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "sensors/barometer.h"
|
||||
#pragma once
|
||||
|
||||
extern int32_t AltHold;
|
||||
extern int32_t vario;
|
||||
|
||||
void calculateEstimatedAltitude(uint32_t currentTime);
|
||||
|
||||
void configureAltitudeHold(pidProfile_t *initialPidProfile, barometerConfig_t *intialBarometerConfig, rcControlsConfig_t *initialRcControlsConfig, escAndServoConfig_t *initialEscAndServoConfig);
|
||||
void applyAltHold(airplaneConfig_t *airplaneConfig);
|
||||
struct pidProfile_s;
|
||||
struct barometerConfig_s;
|
||||
struct rcControlsConfig_s;
|
||||
struct escAndServoConfig_s;
|
||||
void configureAltitudeHold(struct pidProfile_s *initialPidProfile, struct barometerConfig_s *intialBarometerConfig, struct rcControlsConfig_s *initialRcControlsConfig, struct escAndServoConfig_s *initialEscAndServoConfig);
|
||||
|
||||
struct airplaneConfig_t;
|
||||
void applyAltHold(struct airplaneConfig_s *airplaneConfig);
|
||||
void updateAltHoldState(void);
|
||||
void updateSonarAltHoldState(void);
|
||||
|
||||
|
|
|
@ -69,9 +69,10 @@ typedef struct accProcessor_s {
|
|||
accProcessorState_e state;
|
||||
} accProcessor_t;
|
||||
|
||||
struct pidProfile_s;
|
||||
void imuConfigure(
|
||||
imuRuntimeConfig_t *initialImuRuntimeConfig,
|
||||
pidProfile_t *initialPidProfile,
|
||||
struct pidProfile_s *initialPidProfile,
|
||||
accDeadband_t *initialAccDeadband,
|
||||
uint16_t throttle_correction_angle
|
||||
);
|
||||
|
|
|
@ -51,6 +51,8 @@ uint32_t targetPidLooptime;
|
|||
|
||||
bool pidStabilisationEnabled;
|
||||
|
||||
uint8_t PIDweight[3];
|
||||
|
||||
int16_t axisPID[3];
|
||||
|
||||
// PIDweight is a scale factor for PIDs which is derived from the throttle and TPA setting, and 100 = 100% scale means no PID reduction
|
||||
|
|
|
@ -14,7 +14,6 @@
|
|||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "rx/rx.h"
|
||||
|
||||
#pragma once
|
||||
|
||||
|
|
|
@ -63,6 +63,8 @@
|
|||
|
||||
#include "io/display.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
extern profile_t *currentProfile;
|
||||
|
|
|
@ -17,8 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
typedef enum {
|
||||
BOXARM = 0,
|
||||
BOXANGLE,
|
||||
|
@ -167,8 +165,9 @@ typedef struct rcControlsConfig_s {
|
|||
bool areUsingSticksToArm(void);
|
||||
|
||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
||||
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch);
|
||||
struct rxConfig_s;
|
||||
throttleStatus_e calculateThrottleStatus(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||
void processRcStickPositions(struct rxConfig_s *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch);
|
||||
|
||||
bool isRangeActive(uint8_t auxChannelIndex, channelRange_t *range);
|
||||
void updateActivatedModes(modeActivationCondition_t *modeActivationConditions);
|
||||
|
@ -257,7 +256,7 @@ bool isAirmodeActive(void);
|
|||
bool isSuperExpoActive(void);
|
||||
void resetAdjustmentStates(void);
|
||||
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
|
||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
|
||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig, struct rxConfig_s *rxConfig);
|
||||
|
||||
bool isUsingSticksForArming(void);
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/escservo.h"
|
||||
|
||||
#include "io/rc_curves.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
|
||||
|
|
|
@ -17,7 +17,9 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void generateThrottleCurve(controlRateConfig_t *controlRateConfig, escAndServoConfig_t *escAndServoConfig);
|
||||
struct controlRateConfig_s;
|
||||
struct escAndServoConfig_s;
|
||||
void generateThrottleCurve(struct controlRateConfig_s *controlRateConfig, struct escAndServoConfig_s *escAndServoConfig);
|
||||
|
||||
int16_t rcLookup(int32_t tmp, uint8_t expo, uint8_t rate);
|
||||
int16_t rcLookupThrottle(int32_t tmp);
|
||||
|
|
|
@ -23,21 +23,23 @@
|
|||
#include <stdarg.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_4way.h"
|
||||
#include "io/serial_4way_impl.h"
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#include "io/serial_4way_avrootloader.h"
|
||||
|
|
|
@ -17,7 +17,8 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "serial_4way_impl.h"
|
||||
#include "drivers/io_types.h"
|
||||
#include "io/serial_4way_impl.h"
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#define USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
|
@ -46,5 +47,6 @@ typedef union __attribute__ ((packed)) {
|
|||
|
||||
bool isMcuConnected(void);
|
||||
uint8_t esc4wayInit(void);
|
||||
void esc4wayProcess(serialPort_t *mspPort);
|
||||
struct serialPort_s;
|
||||
void esc4wayProcess(struct serialPort_s *mspPort);
|
||||
void esc4wayRelease(void);
|
||||
|
|
|
@ -25,7 +25,8 @@
|
|||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/timer.h"
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
typedef struct {
|
||||
IO_t io;
|
||||
|
|
|
@ -23,7 +23,10 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "config/config.h"
|
||||
#include "io/serial.h"
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
|
|
|
@ -17,9 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
// Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 2 MSP ports.
|
||||
#define MAX_MSP_PORT_COUNT 2
|
||||
|
||||
|
@ -46,7 +43,9 @@ typedef struct mspPort_s {
|
|||
uint8_t cmdMSP;
|
||||
} mspPort_t;
|
||||
|
||||
void mspInit(serialConfig_t *serialConfig);
|
||||
struct serialConfig_s;
|
||||
void mspInit(struct serialConfig_s *serialConfig);
|
||||
void mspProcess(void);
|
||||
void mspAllocateSerialPorts(serialConfig_t *serialConfig);
|
||||
void mspReleasePortIfAllocated(serialPort_t *serialPort);
|
||||
void mspAllocateSerialPorts(struct serialConfig_s *serialConfig);
|
||||
struct serialPort_s;
|
||||
void mspReleasePortIfAllocated(struct serialPort_s *serialPort);
|
||||
|
|
|
@ -32,15 +32,16 @@
|
|||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/pwm.h"
|
||||
#include "rx/sbus.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
@ -51,8 +52,6 @@
|
|||
#include "rx/ibus.h"
|
||||
#include "rx/jetiexbus.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
||||
//#define DEBUG_RX_SIGNAL_LOSS
|
||||
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
struct rxConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool xBusInit(struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
uint8_t xBusFrameStatus(void);
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#include "io/rc_controls.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#define VBATT_PRESENT_THRESHOLD_MV 10
|
||||
#define VBATT_LPF_FREQ 0.4f
|
||||
|
||||
|
|
|
@ -17,17 +17,17 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
typedef enum {
|
||||
FRSKY_VFAS_PRECISION_LOW = 0,
|
||||
FRSKY_VFAS_PRECISION_HIGH
|
||||
} frskyVFasPrecision_e;
|
||||
|
||||
void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
||||
struct rxConfig_s;
|
||||
void handleFrSkyTelemetry(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
|
||||
void checkFrSkyTelemetryState(void);
|
||||
|
||||
void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig);
|
||||
struct telemetryConfig_s;
|
||||
void initFrSkyTelemetry(struct telemetryConfig_s *telemetryConfig);
|
||||
void configureFrSkyTelemetryPort(void);
|
||||
void freeFrSkyTelemetryPort(void);
|
||||
|
||||
|
|
Loading…
Reference in New Issue