1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 22:35:23 +03:00

Remove serial_msp.c's dependency on mw.h/board.h.

This commit is contained in:
Dominic Clifton 2014-04-23 21:38:03 +01:00
parent aa84439b21
commit bb91b1f560
5 changed files with 48 additions and 10 deletions

View file

@ -77,8 +77,8 @@ typedef union {
rollAndPitchTrims_t_def trims; rollAndPitchTrims_t_def trims;
} rollAndPitchTrims_t; } rollAndPitchTrims_t;
extern int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT]; // see gyro_index_t extern int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT];
extern int16_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT]; // see gyro_index_t extern int16_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT];
extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AXIS_COUNT]; extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AXIS_COUNT];
extern int32_t accSum[XYZ_AXIS_COUNT]; extern int32_t accSum[XYZ_AXIS_COUNT];
@ -86,6 +86,11 @@ extern int16_t axisPID[XYZ_AXIS_COUNT];
extern int16_t heading, magHold; extern int16_t heading, magHold;
extern int32_t EstAlt;
extern int32_t AltHold;
extern int32_t EstAlt;
extern int32_t vario;
void mwDisarm(void); void mwDisarm(void);
void setPIDController(int type); void setPIDController(int type);
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims); void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);

View file

@ -56,6 +56,10 @@ typedef struct servoParam_t {
int8_t forwardFromChannel; // RX channel index, 0 based. See CHANNEL_FORWARDING_DISABLED int8_t forwardFromChannel; // RX channel index, 0 based. See CHANNEL_FORWARDING_DISABLED
} servoParam_t; } servoParam_t;
extern int16_t motor[MAX_SUPPORTED_MOTORS];
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
extern int16_t servo[MAX_SUPPORTED_SERVOS];
bool isMixerUsingServos(void); bool isMixerUsingServos(void);
void mixerInit(void); void mixerInit(void);
void writeAllMotors(int16_t mc); void writeAllMotors(int16_t mc);

View file

@ -8,8 +8,6 @@
/* for VBAT monitoring frequency */ /* for VBAT monitoring frequency */
#define VBATFREQ 6 // to read battery voltage - nth number of loop iterations #define VBATFREQ 6 // to read battery voltage - nth number of loop iterations
#define VERSION 230
#include "gimbal.h" #include "gimbal.h"
#include "flight_mixer.h" #include "flight_mixer.h"

View file

@ -1,14 +1,43 @@
#include "board.h" #include <stdbool.h>
#include "mw.h" #include <stdint.h>
#include <string.h>
#include "platform.h"
#include "common/axis.h"
#include "drivers/system_common.h"
#include "drivers/accgyro_common.h"
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "serial_common.h" #include "drivers/bus_i2c.h"
#include "gps_common.h" #include "serial_common.h"
#include "telemetry_common.h"
#include "flight_common.h" #include "flight_common.h"
#include "sensors_compass.h" #include "flight_mixer.h"
#include "rc_controls.h"
#include "boardalignment.h"
#include "gps_common.h"
#include "rx_common.h"
#include "battery.h"
#include "sensors_common.h"
#include "sensors_acceleration.h" #include "sensors_acceleration.h"
#include "sensors_barometer.h"
#include "sensors_compass.h"
#include "sensors_gyro.h"
#include "failsafe.h"
#include "runtime_config.h"
#include "config.h"
#include "config_profile.h"
#include "config_master.h"
#include "version.h"
#include "serial_msp.h"
extern uint16_t cycleTime; // FIXME dependency on mw.c
extern uint16_t rssi; // FIXME dependency on mw.c
extern int16_t debug[4]; // FIXME dependency on mw.c
// Multiwii Serial Protocol 0 // Multiwii Serial Protocol 0
#define MSP_VERSION 0 #define MSP_VERSION 0

2
src/version.h Normal file
View file

@ -0,0 +1,2 @@
#define VERSION 230