1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Move master_t required #includes into config_master.h

This commit is contained in:
Martin Budden 2016-10-01 13:59:48 +01:00
parent 666e922399
commit 9889b1db9c
36 changed files with 207 additions and 783 deletions

View file

@ -16,77 +16,43 @@
*/ */
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h>
#include <string.h> #include <string.h>
#include "platform.h" #include "platform.h"
#ifdef BLACKBOX #ifdef BLACKBOX
#include "build/version.h"
#include "build/debug.h" #include "build/debug.h"
#include "build/version.h"
#include "common/maths.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/color.h"
#include "common/encoding.h" #include "common/encoding.h"
#include "common/utils.h" #include "common/utils.h"
#include "drivers/gpio.h" #include "blackbox.h"
#include "drivers/sensor.h" #include "blackbox_io.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/compass.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/accgyro.h"
#include "drivers/light_led.h"
#include "sensors/sensors.h" #include "drivers/sensor.h"
#include "sensors/boardalignment.h" #include "drivers/compass.h"
#include "sensors/sonar.h" #include "drivers/system.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h" #include "fc/rc_controls.h"
#include "sensors/barometer.h" #include "fc/runtime_config.h"
#include "sensors/gyro.h"
#include "sensors/battery.h" #include "flight/pid.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/display.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "io/gimbal.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/serial.h"
#include "io/serial_cli.h"
#include "io/serial_msp.h"
#include "io/statusindicator.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h" #include "sensors/sensors.h"
#include "rx/msp.h" #include "sensors/compass.h"
#include "sensors/sonar.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/altitudehold.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/pid.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
#include "blackbox.h"
#include "blackbox_io.h"
#define BLACKBOX_I_INTERVAL 32 #define BLACKBOX_I_INTERVAL 32
#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200 #define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
#define SLOW_FRAME_INTERVAL 4096 #define SLOW_FRAME_INTERVAL 4096

View file

@ -17,8 +17,6 @@
#pragma once #pragma once
#include <stdint.h>
typedef enum FlightLogFieldCondition { typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0, FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1,

View file

@ -1,73 +1,33 @@
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h> #include <stdlib.h>
#include <stdarg.h> #include <stdarg.h>
#include <string.h> #include <string.h>
#include "platform.h"
#ifdef BLACKBOX
#include "blackbox_io.h" #include "blackbox_io.h"
#include "build/version.h" #include "build/version.h"
#include "build/build_config.h" #include "build/build_config.h"
#include "common/maths.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/encoding.h" #include "common/encoding.h"
#include "drivers/gpio.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/compass.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/accgyro.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "sensors/sensors.h"
#include "sensors/boardalignment.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/display.h"
#include "io/motors.h"
#include "io/servos.h"
#include "rx/rx.h"
#include "fc/rc_controls.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "io/gimbal.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/serial.h"
#include "io/serial_cli.h"
#include "io/serial_msp.h"
#include "io/statusindicator.h"
#include "rx/msp.h"
#include "telemetry/telemetry.h"
#include "common/printf.h" #include "common/printf.h"
#include "flight/mixer.h" #include "fc/rc_controls.h"
#include "flight/altitudehold.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/pid.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h" #include "flight/pid.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/flashfs.h"
#include "io/serial_msp.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "io/flashfs.h"
#include "io/asyncfatfs/asyncfatfs.h"
#ifdef BLACKBOX
#define BLACKBOX_SERIAL_PORT_MODE MODE_TX #define BLACKBOX_SERIAL_PORT_MODE MODE_TX
// How many bytes can we transmit per loop iteration when writing headers? // How many bytes can we transmit per loop iteration when writing headers?

View file

@ -17,11 +17,6 @@
#pragma once #pragma once
#include <stdint.h>
#include <stdbool.h>
#include "platform.h"
typedef enum BlackboxDevice { typedef enum BlackboxDevice {
BLACKBOX_DEVICE_SERIAL = 0, BLACKBOX_DEVICE_SERIAL = 0,

View file

@ -51,7 +51,7 @@ typedef struct fp_vector {
float Z; float Z;
} t_fp_vector_def; } t_fp_vector_def;
typedef union { typedef union u_fp_vector {
float A[3]; float A[3];
t_fp_vector_def V; t_fp_vector_def V;
} t_fp_vector; } t_fp_vector;

View file

@ -21,53 +21,14 @@
#include "platform.h" #include "platform.h"
#include "build/build_config.h"
#include "common/color.h"
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "sensors/sensors.h" #include "config/config_master.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h" #include "build/build_config.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_eeprom.h" #include "config/config_eeprom.h"
#include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#if !defined(FLASH_SIZE) #if !defined(FLASH_SIZE)

View file

@ -17,6 +17,51 @@
#pragma once #pragma once
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "common/color.h"
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
// System-wide // System-wide
typedef struct master_s { typedef struct master_s {
uint8_t version; uint8_t version;

View file

@ -21,55 +21,11 @@
#include "platform.h" #include "platform.h"
#include "build/build_config.h"
#include "common/color.h"
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
static uint32_t activeFeaturesLatch = 0; static uint32_t activeFeaturesLatch = 0;
void intFeatureSet(uint32_t mask, master_t *config) void intFeatureSet(uint32_t mask, master_t *config)

View file

@ -22,6 +22,7 @@
#ifdef USE_FLASH_M25P16 #ifdef USE_FLASH_M25P16
#include "flash.h"
#include "flash_m25p16.h" #include "flash_m25p16.h"
#include "io.h" #include "io.h"
#include "bus_spi.h" #include "bus_spi.h"

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#include <stdint.h> #include <stdint.h>
#include "flash.h"
#include "io_types.h" #include "io_types.h"
#define M25P16_PAGESIZE 256 #define M25P16_PAGESIZE 256
@ -39,4 +38,5 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length);
bool m25p16_isReady(); bool m25p16_isReady();
bool m25p16_waitForReady(uint32_t timeoutMillis); bool m25p16_waitForReady(uint32_t timeoutMillis);
const flashGeometry_t* m25p16_getGeometry(); struct flashGeometry_s;
const struct flashGeometry_s* m25p16_getGeometry();

View file

@ -24,11 +24,11 @@ typedef enum {
#define PPM_RCVR_TIMEOUT 0 #define PPM_RCVR_TIMEOUT 0
struct timerHardware_s;
void ppmInConfig(const struct timerHardware_s *timerHardwarePtr);
void ppmAvoidPWMTimerClash(const struct timerHardware_s *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer, uint8_t pwmProtocol);
void ppmInConfig(const timerHardware_t *timerHardwarePtr); void pwmInConfig(const struct timerHardware_s *timerHardwarePtr, uint8_t channel);
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer, uint8_t pwmProtocol);
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel);
uint16_t pwmRead(uint8_t channel); uint16_t pwmRead(uint8_t channel);
uint16_t ppmRead(uint8_t channel); uint16_t ppmRead(uint8_t channel);

View file

@ -19,7 +19,8 @@
extern int16_t magHold; extern int16_t magHold;
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta); union rollAndPitchTrims_u;
void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta);
void handleInflightCalibrationStickPosition(); void handleInflightCalibrationStickPosition();
void mwDisarm(void); void mwDisarm(void);

View file

@ -79,14 +79,16 @@ void imuConfigure(
float getCosTiltAngle(void); float getCosTiltAngle(void);
void calculateEstimatedAltitude(uint32_t currentTime); void calculateEstimatedAltitude(uint32_t currentTime);
void imuUpdateAccelerometer(rollAndPitchTrims_t *accelerometerTrims); union rollAndPitchTrims_u;
void imuUpdateAccelerometer(union rollAndPitchTrims_u *accelerometerTrims);
void imuUpdateAttitude(uint32_t currentTime); void imuUpdateAttitude(uint32_t currentTime);
float calculateThrottleAngleScale(uint16_t throttle_correction_angle); float calculateThrottleAngleScale(uint16_t throttle_correction_angle);
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value); int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value);
float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_hz); float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_hz);
int16_t imuCalculateHeading(t_fp_vector *vec); union u_fp_vector;
int16_t imuCalculateHeading(union u_fp_vector *vec);
void imuResetAccelerationSum(void); void imuResetAccelerationSum(void);
void imuUpdateAcc(rollAndPitchTrims_t *accelerometerTrims); void imuUpdateAcc(union rollAndPitchTrims_u *accelerometerTrims);
void imuInit(void); void imuInit(void);

View file

@ -114,7 +114,7 @@ void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
const union rollAndPitchTrims_u *angleTrim, const struct rxConfig_s *rxConfig); const union rollAndPitchTrims_u *angleTrim, const struct rxConfig_s *rxConfig);
extern int16_t axisPID[XYZ_AXIS_COUNT]; extern int16_t axisPID[3];
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
bool airmodeWasActivated; bool airmodeWasActivated;
extern uint32_t targetPidLooptime; extern uint32_t targetPidLooptime;

View file

@ -402,7 +402,7 @@ bool isBeeperOn(void) {
void beeper(beeperMode_e mode) {UNUSED(mode);} void beeper(beeperMode_e mode) {UNUSED(mode);}
void beeperSilence(void) {} void beeperSilence(void) {}
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);} void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
void beeperUpdate(uint32_t currentTime) {} void beeperUpdate(uint32_t currentTime) {UNUSED(currentTime);}
uint32_t getArmingBeepTimeMicros(void) {return 0;} uint32_t getArmingBeepTimeMicros(void) {return 0;}
beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;}
const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;} const char *beeperNameForTableIndex(int idx) {UNUSED(idx); return NULL;}

View file

@ -33,8 +33,10 @@
#include <stdbool.h> #include <stdbool.h>
#include <string.h> #include <string.h>
#include "drivers/flash.h"
#include "drivers/flash_m25p16.h" #include "drivers/flash_m25p16.h"
#include "flashfs.h"
#include "io/flashfs.h"
static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE]; static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];

View file

@ -17,10 +17,6 @@
#pragma once #pragma once
#include <stdint.h>
#include "drivers/flash.h"
#define FLASHFS_WRITE_BUFFER_SIZE 128 #define FLASHFS_WRITE_BUFFER_SIZE 128
#define FLASHFS_WRITE_BUFFER_USABLE (FLASHFS_WRITE_BUFFER_SIZE - 1) #define FLASHFS_WRITE_BUFFER_USABLE (FLASHFS_WRITE_BUFFER_SIZE - 1)
@ -35,7 +31,8 @@ uint32_t flashfsGetOffset();
uint32_t flashfsGetWriteBufferFreeSpace(); uint32_t flashfsGetWriteBufferFreeSpace();
uint32_t flashfsGetWriteBufferSize(); uint32_t flashfsGetWriteBufferSize();
int flashfsIdentifyStartOfFreeSpace(); int flashfsIdentifyStartOfFreeSpace();
const flashGeometry_t* flashfsGetGeometry(); struct flashGeometry_s;
const struct flashGeometry_s* flashfsGetGeometry();
void flashfsSeekAbs(uint32_t offset); void flashfsSeekAbs(uint32_t offset);
void flashfsSeekRel(int32_t offset); void flashfsSeekRel(int32_t offset);

View file

@ -22,91 +22,28 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include <string.h> #include <string.h>
#include <math.h>
#include <ctype.h> #include <ctype.h>
#include "platform.h" #include "platform.h"
#ifdef OSD #ifdef OSD
#include "build/atomic.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "build/version.h" #include "build/version.h"
#include "scheduler/scheduler.h" #include "common/utils.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
#include "common/typeconversion.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "drivers/timer.h"
#include "drivers/serial.h"
#include "drivers/serial_softserial.h"
#include "drivers/serial_uart.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_rx.h"
#include "drivers/adc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/inverter.h"
#include "drivers/flash_m25p16.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/usb_io.h"
#include "drivers/transponder_ir.h"
#include "drivers/sdcard.h"
#include "rx/rx.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "io/gimbal.h"
#include "io/ledstrip.h"
#include "io/display.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/transponder_ir.h"
#include "io/osd.h" #include "io/osd.h"
#include "sensors/sensors.h" #include "fc/rc_controls.h"
#include "sensors/sonar.h"
#include "sensors/barometer.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "sensors/initialisation.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/mixer.h"
#include "flight/failsafe.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/pid.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_eeprom.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"

View file

@ -25,38 +25,46 @@
#include "platform.h" #include "platform.h"
#include "build/version.h" // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
#include "build/debug.h" // signal that we're in cli mode
uint8_t cliMode = 0;
#ifdef USE_CLI
#include "build/build_config.h" #include "build/build_config.h"
#include "build/debug.h"
#include "build/version.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h"
#include "common/color.h" #include "common/color.h"
#include "common/maths.h"
#include "common/printf.h"
#include "common/typeconversion.h" #include "common/typeconversion.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro.h" #include "drivers/accgyro.h"
#include "drivers/compass.h" #include "drivers/compass.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/flash.h"
#include "drivers/gpio.h" #include "drivers/gpio.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/io_impl.h" #include "drivers/io_impl.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/pwm_rx.h" #include "drivers/pwm_rx.h"
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "io/motors.h" #include "io/motors.h"
#include "io/servos.h" #include "io/servos.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "fc/rc_controls.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/serial_cli.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/beeper.h" #include "io/beeper.h"
@ -67,6 +75,8 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/spektrum.h" #include "rx/spektrum.h"
#include "scheduler/scheduler.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
@ -84,25 +94,12 @@
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "telemetry/frsky.h" #include "telemetry/frsky.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_eeprom.h" #include "config/config_eeprom.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
#include "common/printf.h"
#include "io/serial_cli.h"
#include "scheduler/scheduler.h"
// FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
// signal that we're in cli mode
uint8_t cliMode = 0;
#ifdef USE_CLI
extern uint16_t cycleTime; // FIXME dependency on mw.c extern uint16_t cycleTime; // FIXME dependency on mw.c
void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort); void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
@ -1503,12 +1500,13 @@ static void cliAdjustmentRange(char *cmdline)
} }
} }
#ifndef USE_QUAD_MIXER_ONLY
static void printMotorMix(uint8_t dumpMask, master_t *defaultConfig) static void printMotorMix(uint8_t dumpMask, master_t *defaultConfig)
{ {
char buf0[8]; char buf0[8];
char buf1[8]; char buf1[8];
char buf2[8]; char buf2[8];
char buf3[8]; char buf3[8];
for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
if (masterConfig.customMotorMixer[i].throttle == 0.0f) if (masterConfig.customMotorMixer[i].throttle == 0.0f)
break; break;
@ -1537,6 +1535,7 @@ static void printMotorMix(uint8_t dumpMask, master_t *defaultConfig)
ftoa(yaw, buf3)); ftoa(yaw, buf3));
} }
} }
#endif // USE_QUAD_MIXER_ONLY
static void cliMotorMix(char *cmdline) static void cliMotorMix(char *cmdline)
{ {
@ -1548,7 +1547,7 @@ static void cliMotorMix(char *cmdline)
char *ptr; char *ptr;
if (isEmpty(cmdline)) { if (isEmpty(cmdline)) {
printMotorMix(DUMP_MASTER, NULL); printMotorMix(DUMP_MASTER, NULL);
} else if (strncasecmp(cmdline, "reset", 5) == 0) { } else if (strncasecmp(cmdline, "reset", 5) == 0) {
// erase custom mixer // erase custom mixer
for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++)
@ -1597,7 +1596,7 @@ static void cliMotorMix(char *cmdline)
if (check != 4) { if (check != 4) {
cliShowParseError(); cliShowParseError();
} else { } else {
printMotorMix(DUMP_MASTER, NULL); printMotorMix(DUMP_MASTER, NULL);
} }
} else { } else {
cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1); cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
@ -2720,7 +2719,7 @@ static void printConfig(char *cmdline, bool doDiff)
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# mixer\r\n"); cliPrint("\r\n# mixer\r\n");
#endif #endif
bool equalsDefault = masterConfig.mixerMode == defaultConfig.mixerMode; const bool equalsDefault = masterConfig.mixerMode == defaultConfig.mixerMode;
const char *formatMixer = "mixer %s\r\n"; const char *formatMixer = "mixer %s\r\n";
cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[defaultConfig.mixerMode - 1]); cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[defaultConfig.mixerMode - 1]);
cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[masterConfig.mixerMode - 1]); cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[masterConfig.mixerMode - 1]);
@ -2733,33 +2732,33 @@ static void printConfig(char *cmdline, bool doDiff)
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# servo\r\n"); cliPrint("\r\n# servo\r\n");
#endif #endif
printServo(dumpMask, &defaultConfig); printServo(dumpMask, &defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# servo mix\r\n"); cliPrint("\r\n# servo mix\r\n");
#endif #endif
// print custom servo mixer if exists // print custom servo mixer if exists
cliDumpPrintf(dumpMask, masterConfig.customServoMixer[0].rate == 0, "smix reset\r\n\r\n"); cliDumpPrintf(dumpMask, masterConfig.customServoMixer[0].rate == 0, "smix reset\r\n\r\n");
printServoMix(dumpMask, &defaultConfig); printServoMix(dumpMask, &defaultConfig);
#endif #endif
#endif #endif
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# feature\r\n"); cliPrint("\r\n# feature\r\n");
#endif #endif
printFeature(dumpMask, &defaultConfig); printFeature(dumpMask, &defaultConfig);
#ifdef BEEPER #ifdef BEEPER
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# beeper\r\n"); cliPrint("\r\n# beeper\r\n");
#endif #endif
printBeeper(dumpMask, &defaultConfig); printBeeper(dumpMask, &defaultConfig);
#endif #endif
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# map\r\n"); cliPrint("\r\n# map\r\n");
#endif #endif
printMap(dumpMask, &defaultConfig); printMap(dumpMask, &defaultConfig);
#ifndef CLI_MINIMAL_VERBOSITY #ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# serial\r\n"); cliPrint("\r\n# serial\r\n");

View file

@ -27,19 +27,20 @@
#include "build/debug.h" #include "build/debug.h"
#include "build/version.h" #include "build/version.h"
#include "blackbox/blackbox.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/color.h" #include "common/color.h"
#include "common/maths.h" #include "common/maths.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro.h" #include "drivers/accgyro.h"
#include "drivers/compass.h" #include "drivers/compass.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/flash.h"
#include "drivers/gpio.h" #include "drivers/gpio.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/pwm_rx.h" #include "drivers/pwm_rx.h"
@ -47,13 +48,14 @@
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "drivers/max7456.h" #include "drivers/max7456.h"
#include "drivers/vtx_soft_spi_rtc6705.h" #include "drivers/vtx_soft_spi_rtc6705.h"
#include "rx/rx.h"
#include "rx/msp.h" #include "fc/mw.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/motors.h" #include "io/motors.h"
#include "io/servos.h" #include "io/servos.h"
#include "fc/rc_controls.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/serial.h" #include "io/serial.h"
@ -62,10 +64,13 @@
#include "io/transponder_ir.h" #include "io/transponder_ir.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/osd.h" #include "io/osd.h"
#include "io/serial_4way.h"
#include "io/serial_msp.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "io/msp_protocol.h" #include "io/msp_protocol.h"
#include "telemetry/telemetry.h" #include "rx/rx.h"
#include "rx/msp.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
@ -78,6 +83,8 @@
#include "sensors/compass.h" #include "sensors/compass.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/imu.h" #include "flight/imu.h"
@ -85,12 +92,6 @@
#include "flight/navigation.h" #include "flight/navigation.h"
#include "flight/altitudehold.h" #include "flight/altitudehold.h"
#include "blackbox/blackbox.h"
#include "fc/mw.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_eeprom.h" #include "config/config_eeprom.h"
#include "config/config_profile.h" #include "config/config_profile.h"
@ -101,10 +102,6 @@
#include "hardware_revision.h" #include "hardware_revision.h"
#endif #endif
#include "serial_msp.h"
#include "io/serial_4way.h"
static serialPort_t *mspSerialPort; static serialPort_t *mspSerialPort;
extern uint16_t cycleTime; // FIXME dependency on mw.c extern uint16_t cycleTime; // FIXME dependency on mw.c

View file

@ -32,8 +32,9 @@ typedef enum {
#define MSP_PORT_INBUF_SIZE 64 #define MSP_PORT_INBUF_SIZE 64
struct serialPort_s;
typedef struct mspPort_s { typedef struct mspPort_s {
serialPort_t *port; // null when port unused. struct serialPort_s *port; // null when port unused.
uint8_t offset; uint8_t offset;
uint8_t dataSize; uint8_t dataSize;
uint8_t checksum; uint8_t checksum;

View file

@ -17,62 +17,25 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <string.h>
#include "platform.h" #include "platform.h"
#ifdef VTX #ifdef VTX
#include "common/color.h"
#include "common/axis.h"
#include "common/maths.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/vtx_rtc6705.h" #include "drivers/vtx_rtc6705.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "sensors/sensors.h" #include "flight/pid.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_eeprom.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/config_eeprom.h"
#include "fc/runtime_config.h"
static uint8_t locked = 0; static uint8_t locked = 0;

View file

@ -43,6 +43,7 @@
#include "drivers/accgyro_lsm303dlhc.h" #include "drivers/accgyro_lsm303dlhc.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/accgyro_spi_icm20689.h"
#include "drivers/accgyro_spi_mpu6000.h" #include "drivers/accgyro_spi_mpu6000.h"
#include "drivers/accgyro_spi_mpu6500.h" #include "drivers/accgyro_spi_mpu6500.h"
#include "drivers/accgyro_spi_mpu9250.h" #include "drivers/accgyro_spi_mpu9250.h"

View file

@ -15,62 +15,24 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config) void targetConfiguration(master_t *config)
{ {

View file

@ -15,70 +15,35 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h" #include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "flight/failsafe.h"
#include "io/gps.h" #include "flight/mixer.h"
#include "io/osd.h" #include "flight/pid.h"
#include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "telemetry/telemetry.h" #include "sensors/sensors.h"
#include "sensors/compass.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config) { void targetConfiguration(master_t *config)
{
config->mag_hardware = MAG_NONE; // disabled by default config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1; config->rxConfig.spektrum_sat_bind_autoreset = 1;

View file

@ -16,8 +16,6 @@
*/ */
#pragma once #pragma once
#include "drivers/exti.h"
typedef enum awf3HardwareRevision_t { typedef enum awf3HardwareRevision_t {
UNKNOWN = 0, UNKNOWN = 0,
AFF3_REV_1, // MPU6050 / MPU9150 (I2C) AFF3_REV_1, // MPU6050 / MPU9150 (I2C)
@ -29,4 +27,5 @@ extern uint8_t hardwareRevision;
void updateHardwareRevision(void); void updateHardwareRevision(void);
void detectHardwareRevision(void); void detectHardwareRevision(void);
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -15,70 +15,35 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h" #include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h" #include "flight/failsafe.h"
#include "io/gps.h" #include "flight/mixer.h"
#include "io/osd.h" #include "flight/pid.h"
#include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "telemetry/telemetry.h" #include "sensors/sensors.h"
#include "sensors/compass.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// alternative defaults settings for AlienFlight targets // alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config) { void targetConfiguration(master_t *config)
{
config->mag_hardware = MAG_NONE; // disabled by default config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5; config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1; config->rxConfig.spektrum_sat_bind_autoreset = 1;

View file

@ -19,66 +19,11 @@
#include <platform.h> #include <platform.h>
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "hardware_revision.h" #include "hardware_revision.h"
// alternative defaults settings for BlueJayF4 targets // alternative defaults settings for BlueJayF4 targets
void targetConfiguration(master_t *config) void targetConfiguration(master_t *config)
{ {

View file

@ -16,9 +16,7 @@
*/ */
#pragma once #pragma once
#include "drivers/exti.h" typedef enum cjmcuHardwareRevision_t {
typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0, UNKNOWN = 0,
REV_1, // Blue LED3 REV_1, // Blue LED3
REV_2 // Green LED3 REV_2 // Green LED3
@ -31,4 +29,5 @@ void detectHardwareRevision(void);
void spiBusInit(void); void spiBusInit(void);
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -17,68 +17,26 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <string.h>
#include "platform.h" #include "platform.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h" #include "io/motors.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// alternative defaults settings for Colibri/Gemini targets // alternative defaults settings for Colibri/Gemini targets
void targetConfiguration(master_t *config) void targetConfiguration(master_t *config)
{ {

View file

@ -15,70 +15,22 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "build/build_config.h" #include "io/motors.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// alternative defaults settings for COLIBRI RACE targets // alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(master_t *config) { void targetConfiguration(master_t *config)
{
config->motorConfig.minthrottle = 1025; config->motorConfig.minthrottle = 1025;
config->motorConfig.maxthrottle = 1980; config->motorConfig.maxthrottle = 1980;
config->batteryConfig.vbatmaxcellvoltage = 45; config->batteryConfig.vbatmaxcellvoltage = 45;

View file

@ -63,8 +63,10 @@
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_eeprom.h"
#include "config/config_profile.h" #include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h"
#ifdef NAZE #ifdef NAZE
#include "hardware_revision.h" #include "hardware_revision.h"

View file

@ -15,70 +15,18 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "fc/runtime_config.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// Motolab target supports 2 different type of boards Tornado / Cyclone. // Motolab target supports 2 different type of boards Tornado / Cyclone.
void targetConfiguration(master_t *config) { void targetConfiguration(master_t *config)
{
config->gyro_sync_denom = 4; config->gyro_sync_denom = 4;
config->pid_process_denom = 1; config->pid_process_denom = 1;
} }

View file

@ -16,8 +16,6 @@
*/ */
#pragma once #pragma once
#include "drivers/exti.h"
typedef enum nazeHardwareRevision_t { typedef enum nazeHardwareRevision_t {
UNKNOWN = 0, UNKNOWN = 0,
NAZE32, // Naze32 and compatible with 8MHz HSE NAZE32, // Naze32 and compatible with 8MHz HSE
@ -32,4 +30,5 @@ void detectHardwareRevision(void);
void spiBusInit(void); void spiBusInit(void);
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); struct extiConfig_s;
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);

View file

@ -15,70 +15,20 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/serial.h"
#include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "fc/rc_controls.h"
#include "fc/rc_curves.h"
#include "fc/runtime_config.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/gimbal.h"
#include "io/motors.h"
#include "io/servos.h"
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/altitudehold.h"
#include "flight/navigation.h"
#include "config/config.h" #include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h" #include "config/config_master.h"
// alternative defaults settings for COLIBRI RACE targets // alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(master_t *config) { void targetConfiguration(master_t *config)
{
config->rxConfig.sbus_inversion = 0; config->rxConfig.sbus_inversion = 0;
config->rxConfig.rssi_scale = 19; config->rxConfig.rssi_scale = 19;
config->rxConfig.serialrx_provider = SERIALRX_SBUS; config->rxConfig.serialrx_provider = SERIALRX_SBUS;

View file

@ -16,8 +16,6 @@
*/ */
#pragma once #pragma once
#include "drivers/exti.h"
extern uint8_t hardwareRevision; extern uint8_t hardwareRevision;
void updateHardwareRevision(void); void updateHardwareRevision(void);