Fix some targets

This commit is contained in:
borisbstyle 2016-11-30 23:34:50 +01:00
parent e9083db022
commit 907a184018
8 changed files with 44 additions and 37 deletions

View File

@ -32,7 +32,7 @@
#define CROSSFIRE_RSSI_FRAME_ID 0x14
#define CLEANFLIGHT_MODE_FRAME_ID 0x20
#define DATA_BUFFER_SIZE 64
#define DATA_BUFFER_SIZE 128
typedef enum BSTDevice {
BSTDEV_1,

View File

@ -1518,6 +1518,7 @@ void taskBstMasterProcess(uint32_t currentTime)
if(sensors(SENSOR_GPS) && !bstWriteBusy())
writeGpsPositionPrameToBST();
}
bstMasterWriteLoop();
if (isRebootScheduled) {
@ -1549,22 +1550,25 @@ static void bstMasterWrite16(uint16_t data)
bstMasterWrite8((uint8_t)(data >> 0));
}
/*************************************************************************************************/
#define PUBLIC_ADDRESS 0x00
#ifdef GPS
static void bstMasterWrite32(uint32_t data)
{
bstMasterWrite16((uint8_t)(data >> 16));
bstMasterWrite16((uint8_t)(data >> 0));
}
/*************************************************************************************************/
#define PUBLIC_ADDRESS 0x00
static int32_t lat = 0;
static int32_t lon = 0;
static uint16_t alt = 0;
static uint8_t numOfSat = 0;
#endif
bool writeGpsPositionPrameToBST(void)
{
#ifdef GPS
if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) {
lat = GPS_coord[LAT];
lon = GPS_coord[LON];
@ -1589,6 +1593,9 @@ bool writeGpsPositionPrameToBST(void)
return bstMasterWrite(masterWriteData);
} else
return false;
#else
return true;
#endif
}
bool writeRollPitchYawToBST(void)

View File

@ -148,9 +148,9 @@
#define LED_STRIP
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
//#define SONAR
//#define SONAR_ECHO_PIN PB1
//#define SONAR_TRIGGER_PIN PB0
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM

View File

@ -45,14 +45,14 @@
#define BMP280_SPI_INSTANCE SPI1
#define BMP280_CS_PIN PA13
#define BARO
#define USE_BARO_BMP280
#define USE_BARO_SPI_BMP280
//#define BARO
//#define USE_BARO_BMP280
//#define USE_BARO_SPI_BMP280
#define MAG // External
#define USE_MAG_AK8963
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
//#define MAG // External
//#define USE_MAG_AK8963
//#define USE_MAG_AK8975
//#define USE_MAG_HMC5883
//#define SONAR
//#define SONAR_ECHO_PIN PB1

View File

@ -109,15 +109,15 @@
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
#define NAV
#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION
#define NAV_MAX_WAYPOINTS 60
#define GPS
//#define NAV
//#define NAV_AUTO_MAG_DECLINATION
//#define NAV_GPS_GLITCH_DETECTION
//#define NAV_MAX_WAYPOINTS 60
//#define GPS
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
//#define AUTOTUNE
#define USE_SERVOS
#define USE_CLI

View File

@ -55,10 +55,10 @@
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define MAG
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW270_DEG
//#define MAG
//#define USE_MAG_AK8975
//#define USE_MAG_HMC5883
//#define MAG_HMC5883_ALIGN CW270_DEG
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
@ -69,9 +69,9 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define SONAR
#define SONAR_TRIGGER_PIN PB0
#define SONAR_ECHO_PIN PB1
//#define SONAR
//#define SONAR_TRIGGER_PIN PB0
//#define SONAR_ECHO_PIN PB1
#define USE_UART1
#define USE_UART2

View File

@ -50,8 +50,8 @@
#define BARO
#define USE_BARO_BMP280
#define MAG
#define USE_MAG_AK8963
//#define MAG
//#define USE_MAG_AK8963
//#define USE_MAG_HMC5883 // External
#define MAG_AK8963_ALIGN CW90_DEG_FLIP

View File

@ -51,15 +51,15 @@
#define BARO
#define USE_BARO_BMP280
#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
//#define MAG
//#define USE_MPU9250_MAG // Enables bypass configuration
//#define USE_MAG_AK8975
//#define USE_MAG_HMC5883 // External
//#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
//#define SONAR
//#define SONAR_ECHO_PIN PB1
//#define SONAR_TRIGGER_PIN PB0
#define USB_IO
#define USB_CABLE_DETECTION