mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-20 06:45:14 +03:00
Removed #includes from header files and other betaflight catchups
This commit is contained in:
parent
f440eadc03
commit
19ab505e6a
80 changed files with 174 additions and 117 deletions
|
@ -119,6 +119,7 @@ int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list
|
|||
#define printf tfp_printf
|
||||
#define sprintf tfp_sprintf
|
||||
|
||||
void printfSupportInit(void);
|
||||
void setPrintfSerialPort(serialPort_t *serialPort);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
#include "sensor.h"
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#include "nvic.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "exti.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io_types.h"
|
||||
#include "exti.h"
|
||||
|
||||
// MPU6050
|
||||
|
|
|
@ -27,6 +27,8 @@
|
|||
#include "adc.h"
|
||||
#include "adc_impl.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
//#define DEBUG_ADC_CHANNELS
|
||||
|
||||
#ifdef USE_ADC
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io.h"
|
||||
#include "io_types.h"
|
||||
|
||||
typedef enum {
|
||||
ADC_BATTERY = 0,
|
||||
|
|
|
@ -17,8 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
#include "io_types.h"
|
||||
#include "rcc_types.h"
|
||||
|
||||
#if defined(STM32F4)
|
||||
#define ADC_TAG_MAP_COUNT 16
|
||||
|
|
|
@ -22,7 +22,6 @@
|
|||
|
||||
#include "barometer.h"
|
||||
|
||||
#include "gpio.h"
|
||||
#include "system.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#include "build_config.h"
|
||||
#include "bus_i2c.h"
|
||||
#include "drivers/io.h"
|
||||
#include "io.h"
|
||||
|
||||
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
|
||||
// Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7)
|
||||
|
|
|
@ -20,9 +20,10 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "gpio.h"
|
||||
#include "system.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#include "bus_i2c.h"
|
||||
|
||||
|
|
|
@ -33,9 +33,6 @@
|
|||
#include "bus_i2c.h"
|
||||
#include "bus_spi.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "sensor.h"
|
||||
#include "compass.h"
|
||||
|
||||
|
|
|
@ -33,8 +33,6 @@
|
|||
#include "gpio.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "sensor.h"
|
||||
#include "compass.h"
|
||||
|
||||
|
@ -157,4 +155,3 @@ bool ak8975Read(int16_t *magData)
|
|||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -39,8 +39,6 @@
|
|||
#include "sensor.h"
|
||||
#include "compass.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "compass_hmc5883l.h"
|
||||
|
||||
//#define DEBUG_MAG_DATA_READY_INTERRUPT
|
||||
|
@ -274,5 +272,4 @@ bool hmc5883lRead(int16_t *magData)
|
|||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io.h"
|
||||
#include "io_types.h"
|
||||
|
||||
typedef struct hmc5883Config_s {
|
||||
ioTag_t intTag;
|
||||
|
|
|
@ -21,8 +21,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "nvic.h"
|
||||
#include "dma.h"
|
||||
|
||||
/*
|
||||
* DMA descriptors.
|
||||
|
|
|
@ -21,8 +21,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "nvic.h"
|
||||
#include "dma.h"
|
||||
|
||||
/*
|
||||
* DMA descriptors.
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "io_types.h"
|
||||
|
||||
// old EXTI interface, to be replaced
|
||||
typedef struct extiConfig_s {
|
||||
|
|
|
@ -6,16 +6,7 @@
|
|||
#include <platform.h>
|
||||
#include "resource.h"
|
||||
|
||||
// IO pin identification
|
||||
// make sure that ioTag_t can't be assigned into IO_t without warning
|
||||
typedef uint8_t ioTag_t; // packet tag to specify IO pin
|
||||
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
|
||||
|
||||
// NONE initializer for ioTag_t variables
|
||||
#define IOTAG_NONE ((ioTag_t)0)
|
||||
|
||||
// NONE initializer for IO_t variable
|
||||
#define IO_NONE ((IO_t)0)
|
||||
#include "io_types.h"
|
||||
|
||||
// preprocessor is used to convert pinid to requested C data value
|
||||
// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx)
|
||||
|
@ -24,19 +15,6 @@ typedef void* IO_t; // type specifying IO pin. Currently ioRec_t poin
|
|||
// expand pinid to to ioTag_t
|
||||
#define IO_TAG(pinid) DEFIO_TAG(pinid)
|
||||
|
||||
// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
|
||||
// this simplifies initialization (globals are zeroed on start) and allows
|
||||
// omitting unused fields in structure initializers.
|
||||
// it is also possible to use IO_t and ioTag_t as boolean value
|
||||
// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
|
||||
// IO_t being pointer is only possibility I know of ..
|
||||
|
||||
// pin config handling
|
||||
// pin config is packed into ioConfig_t to decrease memory requirements
|
||||
// IOCFG_x macros are defined for common combinations for all CPUs; this
|
||||
// helps masking CPU differences
|
||||
|
||||
typedef uint8_t ioConfig_t; // packed IO configuration
|
||||
#if defined(STM32F1)
|
||||
|
||||
// mode is using only bits 6-2
|
||||
|
|
28
src/main/drivers/io_types.h
Normal file
28
src/main/drivers/io_types.h
Normal file
|
@ -0,0 +1,28 @@
|
|||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// IO pin identification
|
||||
// make sure that ioTag_t can't be assigned into IO_t without warning
|
||||
typedef uint8_t ioTag_t; // packet tag to specify IO pin
|
||||
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
|
||||
|
||||
// NONE initializer for ioTag_t variables
|
||||
#define IOTAG_NONE ((ioTag_t)0)
|
||||
|
||||
// NONE initializer for IO_t variable
|
||||
#define IO_NONE ((IO_t)0)
|
||||
|
||||
// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
|
||||
// this simplifies initialization (globals are zeroed on start) and allows
|
||||
// omitting unused fields in structure initializers.
|
||||
// it is also possible to use IO_t and ioTag_t as boolean value
|
||||
// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment
|
||||
// IO_t being pointer is only possibility I know of ..
|
||||
|
||||
// pin config handling
|
||||
// pin config is packed into ioConfig_t to decrease memory requirements
|
||||
// IOCFG_x macros are defined for common combinations for all CPUs; this
|
||||
// helps masking CPU differences
|
||||
|
||||
typedef uint8_t ioConfig_t; // packed IO configuration
|
|
@ -36,8 +36,8 @@
|
|||
|
||||
#include "common/color.h"
|
||||
#include "common/colorconversion.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "dma.h"
|
||||
#include "light_ws2811strip.h"
|
||||
|
||||
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
volatile uint8_t ws2811LedDataTransferInProgress = 0;
|
||||
|
|
|
@ -23,10 +23,11 @@
|
|||
#ifdef LED_STRIP
|
||||
|
||||
#include "common/color.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "light_ws2811strip.h"
|
||||
#include "nvic.h"
|
||||
#include "io.h"
|
||||
#include "dma.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include "nvic.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "light_ws2811strip.h"
|
||||
#include "dma.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "timer.h"
|
||||
#include "io_types.h"
|
||||
|
||||
#if defined(USE_QUAD_MIXER_ONLY)
|
||||
#define MAX_PWM_MOTORS 4
|
||||
|
@ -101,10 +101,11 @@ typedef enum {
|
|||
PWM_PF_PWM = (1 << 6)
|
||||
} pwmPortFlags_e;
|
||||
|
||||
struct timerHardware_s;
|
||||
typedef struct pwmPortConfiguration_s {
|
||||
uint8_t index;
|
||||
pwmPortFlags_e flags;
|
||||
const timerHardware_t *timerHardware;
|
||||
const struct timerHardware_s *timerHardware;
|
||||
} pwmPortConfiguration_t;
|
||||
|
||||
typedef struct pwmIOConfiguration_s {
|
||||
|
@ -145,4 +146,5 @@ extern const uint16_t multiPWM[];
|
|||
extern const uint16_t airPPM[];
|
||||
extern const uint16_t airPWM[];
|
||||
|
||||
pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
||||
pwmIOConfiguration_t *pwmGetOutputConfiguration(void);
|
||||
|
|
|
@ -27,8 +27,6 @@
|
|||
#include "io_impl.h"
|
||||
#include "timer.h"
|
||||
|
||||
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
|
||||
|
||||
#include "pwm_mapping.h"
|
||||
|
||||
#include "pwm_output.h"
|
||||
|
|
|
@ -30,9 +30,10 @@
|
|||
#include "system.h"
|
||||
|
||||
#include "nvic.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "timer.h"
|
||||
|
||||
#include "pwm_output.h"
|
||||
#include "pwm_mapping.h"
|
||||
|
||||
#include "pwm_rx.h"
|
||||
|
|
|
@ -1,7 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
#include "platform.h"
|
||||
#include "common/utils.h"
|
||||
#include "rcc_types.h"
|
||||
|
||||
enum rcc_reg {
|
||||
RCC_EMPTY = 0, // make sure that default value (0) does not enable anything
|
||||
|
@ -17,9 +16,6 @@ enum rcc_reg {
|
|||
#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN)
|
||||
#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN)
|
||||
|
||||
typedef uint8_t rccPeriphTag_t;
|
||||
|
||||
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
|
||||
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
|
||||
|
||||
|
||||
|
|
4
src/main/drivers/rcc_types.h
Normal file
4
src/main/drivers/rcc_types.h
Normal file
|
@ -0,0 +1,4 @@
|
|||
#pragma once
|
||||
|
||||
typedef uint8_t rccPeriphTag_t;
|
||||
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#include "build_config.h"
|
||||
#include "common/utils.h"
|
||||
#include "drivers/io.h"
|
||||
#include "io.h"
|
||||
|
||||
#include "usb_core.h"
|
||||
#ifdef STM32F4
|
||||
|
@ -32,7 +32,7 @@
|
|||
#include "hw_config.h"
|
||||
#endif
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "system.h"
|
||||
|
||||
#include "serial.h"
|
||||
#include "serial_usb_vcp.h"
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "io_types.h"
|
||||
|
||||
#ifdef BEEPER
|
||||
#define BEEP_TOGGLE systemBeepToggle()
|
||||
|
|
|
@ -67,4 +67,3 @@ void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
|
|||
|
||||
extern uint32_t cachedRccCsrValue;
|
||||
|
||||
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||
|
||||
// from system_stm32f10x.c
|
||||
void SetSysClock(void);
|
||||
void SetSysClock(bool overclock);
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
|
@ -70,7 +70,7 @@ void systemInit(void)
|
|||
{
|
||||
checkForBootLoaderRequest();
|
||||
|
||||
SetSysClock();
|
||||
SetSysClock(false);
|
||||
|
||||
#ifdef CC3D
|
||||
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include "system.h"
|
||||
|
||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||
void SetSysClock();
|
||||
void SetSysClock(void);
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "accgyro_mpu.h"
|
||||
#include "gpio.h"
|
||||
#include "exti.h"
|
||||
#include "nvic.h"
|
||||
#include "system.h"
|
||||
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
|
||||
#include "nvic.h"
|
||||
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
#include "system.h"
|
||||
|
||||
|
|
|
@ -17,12 +17,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#if !defined(USABLE_TIMER_CHANNEL_COUNT)
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#endif
|
||||
#include "io_types.h"
|
||||
#include "rcc_types.h"
|
||||
|
||||
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
|
||||
|
||||
|
|
|
@ -5,6 +5,13 @@
|
|||
http://www.st.com/software_license_agreement_liberty_v2
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
|
|
@ -5,6 +5,13 @@
|
|||
http://www.st.com/software_license_agreement_liberty_v2
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "stm32f30x.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
|
|
@ -5,9 +5,16 @@
|
|||
http://www.st.com/software_license_agreement_liberty_v2
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "stm32f4xx.h"
|
||||
#include "timer.h"
|
||||
#include "rcc.h"
|
||||
#include "timer.h"
|
||||
|
||||
/**
|
||||
* @brief Selects the TIM Output Compare Mode.
|
||||
|
|
|
@ -81,6 +81,8 @@ typedef struct failsafeState_s {
|
|||
failsafeRxLinkState_e rxLinkState;
|
||||
} failsafeState_t;
|
||||
|
||||
struct rxConfig_s;
|
||||
void failsafeInit(struct rxConfig_s *intialRxConfig, uint16_t deadband3d_throttle);
|
||||
void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse);
|
||||
failsafeConfig_t * getActiveFailsafeConfig(void);
|
||||
|
||||
|
|
|
@ -17,8 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#define GRAVITY_CMSS 980.665f
|
||||
|
||||
extern int16_t throttleAngleCorrection;
|
||||
|
@ -48,7 +46,8 @@ typedef struct imuRuntimeConfig_s {
|
|||
uint8_t small_angle;
|
||||
} imuRuntimeConfig_t;
|
||||
|
||||
void imuConfigure(imuRuntimeConfig_t *initialImuRuntimeConfig, pidProfile_t *initialPidProfile);
|
||||
struct pidProfile_s;
|
||||
void imuConfigure(imuRuntimeConfig_t *initialImuRuntimeConfig, struct pidProfile_s *initialPidProfile);
|
||||
|
||||
void imuUpdateGyroAndAttitude(void);
|
||||
void imuUpdateAccelerometer(void);
|
||||
|
@ -61,3 +60,4 @@ void imuTransformVectorBodyToEarth(t_fp_vector * v);
|
|||
void imuTransformVectorEarthToBody(t_fp_vector * v);
|
||||
|
||||
int16_t imuCalculateHeading(t_fp_vector *vec);
|
||||
void imuInit(void);
|
||||
|
|
|
@ -235,7 +235,11 @@ void mixerLoadMix(int index, motorMixer_t *customMixers);
|
|||
void servoMixerLoadMix(int index, servoMixer_t *customServoMixers);
|
||||
void loadCustomServoMixer(void);
|
||||
int servoDirection(int servoIndex, int fromChannel);
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMotorMixers, servoMixer_t *initialCustomServoMixers);
|
||||
#else
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMixers);
|
||||
#endif
|
||||
void mixerUsePWMIOConfiguration(void);
|
||||
void mixerResetDisarmedMotors(void);
|
||||
void mixTable(void);
|
||||
void writeMotors(void);
|
||||
|
|
|
@ -21,6 +21,8 @@ typedef enum {
|
|||
PAGE_STATUS
|
||||
} pageId_e;
|
||||
|
||||
struct rxConfig_s;
|
||||
void displayInit(struct rxConfig_s *intialRxConfig);
|
||||
void updateDisplay(void);
|
||||
|
||||
void displaySetPage(pageId_e newPageId);
|
||||
|
|
|
@ -132,5 +132,8 @@ typedef struct {
|
|||
extern gpsSolutionData_t gpsSol;
|
||||
extern gpsStatistics_t gpsStats;
|
||||
|
||||
void gpsPreInit(gpsConfig_t *initialGpsConfig);
|
||||
struct serialConfig_s;
|
||||
void gpsInit(struct serialConfig_s *serialConfig, gpsConfig_t *initialGpsConfig);
|
||||
void gpsThread(void);
|
||||
void updateGpsIndicator(uint32_t currentTime);
|
||||
|
|
|
@ -15,12 +15,12 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef CLI_H_
|
||||
#define CLI_H_
|
||||
#pragma once
|
||||
|
||||
extern uint8_t cliMode;
|
||||
|
||||
struct serialConfig_s;
|
||||
void cliInit(struct serialConfig_s *serialConfig);
|
||||
void cliProcess(void);
|
||||
bool cliIsActiveOnPort(serialPort_t *serialPort);
|
||||
|
||||
#endif /* CLI_H_ */
|
||||
struct serialPort_s;
|
||||
bool cliIsActiveOnPort(struct serialPort_s *serialPort);
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#include "common/color.h"
|
||||
#include "common/atomic.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
|
||||
|
@ -33,6 +34,7 @@
|
|||
#include "drivers/dma.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
#include "drivers/timer.h"
|
||||
|
@ -43,6 +45,7 @@
|
|||
#include "drivers/compass.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
@ -55,6 +58,7 @@
|
|||
#include "drivers/exti.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -66,6 +70,8 @@
|
|||
#include "io/ledstrip.h"
|
||||
#include "io/display.h"
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/serial_cli.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
|
@ -77,6 +83,7 @@
|
|||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/initialisation.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
@ -105,27 +112,6 @@ extern uint8_t motorControlEnable;
|
|||
serialPort_t *loopbackPort;
|
||||
#endif
|
||||
|
||||
void printfSupportInit(void);
|
||||
void timerInit(void);
|
||||
void telemetryInit(void);
|
||||
void mspInit();
|
||||
void cliInit(serialConfig_t *serialConfig);
|
||||
void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle);
|
||||
pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init);
|
||||
#ifdef USE_SERVOS
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixer_t *customServoMixers);
|
||||
#else
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers);
|
||||
#endif
|
||||
void mixerUsePWMIOConfiguration(void);
|
||||
void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions);
|
||||
void gpsPreInit(gpsConfig_t *initialGpsConfig);
|
||||
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig);
|
||||
void imuInit(void);
|
||||
void displayInit(rxConfig_t *intialRxConfig);
|
||||
void spektrumBind(rxConfig_t *rxConfig);
|
||||
const sonarHcsr04Hardware_t *sonarGetHardwareConfiguration(currentSensor_e currentSensor);
|
||||
|
||||
typedef enum {
|
||||
SYSTEM_STATE_INITIALISING = 0,
|
||||
SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
|
||||
|
@ -391,6 +377,7 @@ void init(void)
|
|||
adcInit(&adc_params);
|
||||
#endif
|
||||
|
||||
|
||||
initBoardAlignment(&masterConfig.boardAlignment);
|
||||
|
||||
#ifdef DISPLAY
|
||||
|
@ -441,7 +428,7 @@ void init(void)
|
|||
|
||||
imuInit();
|
||||
|
||||
mspInit(&masterConfig.serialConfig);
|
||||
mspInit();
|
||||
|
||||
#ifdef USE_CLI
|
||||
cliInit(&masterConfig.serialConfig);
|
||||
|
|
|
@ -141,6 +141,8 @@ typedef struct rxRuntimeConfig_s {
|
|||
|
||||
extern rxRuntimeConfig_t rxRuntimeConfig;
|
||||
|
||||
struct modeActivationCondition_s;
|
||||
void rxInit(rxConfig_t *rxConfig, struct modeActivationCondition_s *modeActivationConditions);
|
||||
void useRxConfig(rxConfig_t *rxConfigToUse);
|
||||
|
||||
typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
||||
|
|
|
@ -21,4 +21,7 @@
|
|||
#define SPEKTRUM_SAT_BIND_MAX 10
|
||||
|
||||
uint8_t spektrumFrameStatus(void);
|
||||
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
struct rxConfig_s;
|
||||
void spektrumBind(struct rxConfig_s *rxConfig);
|
||||
struct rxRuntimeConfig_s;
|
||||
bool spektrumInit(struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/exti.h"
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
#include "drivers/sonar.h"
|
||||
#include "drivers/rangefinder.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
typedef enum {
|
||||
|
@ -32,7 +32,8 @@ typedef enum {
|
|||
SONAR_HCSR04_PINS_PWM,
|
||||
} sonarHCSR04Pins_e;
|
||||
|
||||
typedef void (*sonarInitFunctionPtr)(sonarRange_t *sonarRange);
|
||||
struct sonarRange_s;
|
||||
typedef void (*sonarInitFunctionPtr)(struct sonarRange_s *sonarRange);
|
||||
typedef void (*sonarUpdateFunctionPtr)(void);
|
||||
typedef int32_t (*sonarReadFunctionPtr)(void);
|
||||
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
#ifdef CC3D_PPM1
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -106,4 +106,5 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 (M2)
|
||||
|
|
|
@ -84,4 +84,5 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS TIM_N(2)
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -110,5 +110,6 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
|
||||
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -146,8 +146,8 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
|
||||
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
#define I2C1_SCL_PIN PB8
|
||||
#define I2C1_SDA_PIN PB9
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define USE_ADC
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -220,4 +220,5 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -95,4 +95,5 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -128,5 +128,6 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
|
||||
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -158,4 +158,5 @@
|
|||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
@ -100,8 +101,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
|
||||
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
|
|
@ -82,5 +82,6 @@
|
|||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF 0x00ff
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))
|
||||
|
||||
|
|
|
@ -5,12 +5,13 @@ TARGET_SRC = \
|
|||
drivers/accgyro_adxl345.c \
|
||||
drivers/accgyro_bma280.c \
|
||||
drivers/accgyro_l3gd20.c \
|
||||
drivers/accgyro_l3g4200d.c \
|
||||
drivers/accgyro_lsm303dlhc.c \
|
||||
drivers/accgyro_mma845x.c \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu3050.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/accgyro_l3g4200d.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8975.c \
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
#include "build_config.h"
|
||||
|
||||
#if defined(TELEMETRY) && defined(TELEMETRY_LTM)
|
||||
#if defined(TELEMETRY_LTM)
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
@ -268,6 +268,7 @@ static void ltm_nframe(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(GPS)
|
||||
static bool ltm_shouldSendXFrame(void)
|
||||
{
|
||||
static uint16_t lastHDOP = 0;
|
||||
|
@ -279,6 +280,7 @@ static bool ltm_shouldSendXFrame(void)
|
|||
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
#define LTM_BIT_AFRAME (1 << 0)
|
||||
#define LTM_BIT_GFRAME (1 << 1)
|
||||
|
|
|
@ -46,6 +46,7 @@ typedef struct telemetryConfig_s {
|
|||
uint8_t hottAlarmSoundInterval;
|
||||
} telemetryConfig_t;
|
||||
|
||||
void telemetryInit(void);
|
||||
bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig);
|
||||
extern serialPort_t *telemetrySharedPort;
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue