Fix some targets
This commit is contained in:
parent
e9083db022
commit
907a184018
|
@ -32,7 +32,7 @@
|
||||||
#define CROSSFIRE_RSSI_FRAME_ID 0x14
|
#define CROSSFIRE_RSSI_FRAME_ID 0x14
|
||||||
#define CLEANFLIGHT_MODE_FRAME_ID 0x20
|
#define CLEANFLIGHT_MODE_FRAME_ID 0x20
|
||||||
|
|
||||||
#define DATA_BUFFER_SIZE 64
|
#define DATA_BUFFER_SIZE 128
|
||||||
|
|
||||||
typedef enum BSTDevice {
|
typedef enum BSTDevice {
|
||||||
BSTDEV_1,
|
BSTDEV_1,
|
||||||
|
|
|
@ -1518,6 +1518,7 @@ void taskBstMasterProcess(uint32_t currentTime)
|
||||||
|
|
||||||
if(sensors(SENSOR_GPS) && !bstWriteBusy())
|
if(sensors(SENSOR_GPS) && !bstWriteBusy())
|
||||||
writeGpsPositionPrameToBST();
|
writeGpsPositionPrameToBST();
|
||||||
|
|
||||||
}
|
}
|
||||||
bstMasterWriteLoop();
|
bstMasterWriteLoop();
|
||||||
if (isRebootScheduled) {
|
if (isRebootScheduled) {
|
||||||
|
@ -1549,22 +1550,25 @@ static void bstMasterWrite16(uint16_t data)
|
||||||
bstMasterWrite8((uint8_t)(data >> 0));
|
bstMasterWrite8((uint8_t)(data >> 0));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*************************************************************************************************/
|
||||||
|
#define PUBLIC_ADDRESS 0x00
|
||||||
|
|
||||||
|
#ifdef GPS
|
||||||
static void bstMasterWrite32(uint32_t data)
|
static void bstMasterWrite32(uint32_t data)
|
||||||
{
|
{
|
||||||
bstMasterWrite16((uint8_t)(data >> 16));
|
bstMasterWrite16((uint8_t)(data >> 16));
|
||||||
bstMasterWrite16((uint8_t)(data >> 0));
|
bstMasterWrite16((uint8_t)(data >> 0));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*************************************************************************************************/
|
|
||||||
#define PUBLIC_ADDRESS 0x00
|
|
||||||
|
|
||||||
static int32_t lat = 0;
|
static int32_t lat = 0;
|
||||||
static int32_t lon = 0;
|
static int32_t lon = 0;
|
||||||
static uint16_t alt = 0;
|
static uint16_t alt = 0;
|
||||||
static uint8_t numOfSat = 0;
|
static uint8_t numOfSat = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
bool writeGpsPositionPrameToBST(void)
|
bool writeGpsPositionPrameToBST(void)
|
||||||
{
|
{
|
||||||
|
#ifdef GPS
|
||||||
if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) {
|
if((lat != GPS_coord[LAT]) || (lon != GPS_coord[LON]) || (alt != GPS_altitude) || (numOfSat != GPS_numSat)) {
|
||||||
lat = GPS_coord[LAT];
|
lat = GPS_coord[LAT];
|
||||||
lon = GPS_coord[LON];
|
lon = GPS_coord[LON];
|
||||||
|
@ -1589,6 +1593,9 @@ bool writeGpsPositionPrameToBST(void)
|
||||||
return bstMasterWrite(masterWriteData);
|
return bstMasterWrite(masterWriteData);
|
||||||
} else
|
} else
|
||||||
return false;
|
return false;
|
||||||
|
#else
|
||||||
|
return true;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
bool writeRollPitchYawToBST(void)
|
bool writeRollPitchYawToBST(void)
|
||||||
|
|
|
@ -148,9 +148,9 @@
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
#define SONAR
|
//#define SONAR
|
||||||
#define SONAR_ECHO_PIN PB1
|
//#define SONAR_ECHO_PIN PB1
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
//#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
|
@ -45,14 +45,14 @@
|
||||||
#define BMP280_SPI_INSTANCE SPI1
|
#define BMP280_SPI_INSTANCE SPI1
|
||||||
#define BMP280_CS_PIN PA13
|
#define BMP280_CS_PIN PA13
|
||||||
|
|
||||||
#define BARO
|
//#define BARO
|
||||||
#define USE_BARO_BMP280
|
//#define USE_BARO_BMP280
|
||||||
#define USE_BARO_SPI_BMP280
|
//#define USE_BARO_SPI_BMP280
|
||||||
|
|
||||||
#define MAG // External
|
//#define MAG // External
|
||||||
#define USE_MAG_AK8963
|
//#define USE_MAG_AK8963
|
||||||
#define USE_MAG_AK8975
|
//#define USE_MAG_AK8975
|
||||||
#define USE_MAG_HMC5883
|
//#define USE_MAG_HMC5883
|
||||||
|
|
||||||
//#define SONAR
|
//#define SONAR
|
||||||
//#define SONAR_ECHO_PIN PB1
|
//#define SONAR_ECHO_PIN PB1
|
||||||
|
|
|
@ -109,15 +109,15 @@
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
|
|
||||||
#define NAV
|
//#define NAV
|
||||||
#define NAV_AUTO_MAG_DECLINATION
|
//#define NAV_AUTO_MAG_DECLINATION
|
||||||
#define NAV_GPS_GLITCH_DETECTION
|
//#define NAV_GPS_GLITCH_DETECTION
|
||||||
#define NAV_MAX_WAYPOINTS 60
|
//#define NAV_MAX_WAYPOINTS 60
|
||||||
#define GPS
|
//#define GPS
|
||||||
#define BLACKBOX
|
#define BLACKBOX
|
||||||
#define TELEMETRY
|
#define TELEMETRY
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
#define AUTOTUNE
|
//#define AUTOTUNE
|
||||||
#define USE_SERVOS
|
#define USE_SERVOS
|
||||||
#define USE_CLI
|
#define USE_CLI
|
||||||
|
|
||||||
|
|
|
@ -55,10 +55,10 @@
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
#define USE_BARO_BMP085
|
#define USE_BARO_BMP085
|
||||||
|
|
||||||
#define MAG
|
//#define MAG
|
||||||
#define USE_MAG_AK8975
|
//#define USE_MAG_AK8975
|
||||||
#define USE_MAG_HMC5883
|
//#define USE_MAG_HMC5883
|
||||||
#define MAG_HMC5883_ALIGN CW270_DEG
|
//#define MAG_HMC5883_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
|
@ -69,9 +69,9 @@
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define SONAR
|
//#define SONAR
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
//#define SONAR_TRIGGER_PIN PB0
|
||||||
#define SONAR_ECHO_PIN PB1
|
//#define SONAR_ECHO_PIN PB1
|
||||||
|
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
#define USE_UART2
|
#define USE_UART2
|
||||||
|
|
|
@ -50,8 +50,8 @@
|
||||||
#define BARO
|
#define BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
||||||
#define MAG
|
//#define MAG
|
||||||
#define USE_MAG_AK8963
|
//#define USE_MAG_AK8963
|
||||||
//#define USE_MAG_HMC5883 // External
|
//#define USE_MAG_HMC5883 // External
|
||||||
|
|
||||||
#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
#define MAG_AK8963_ALIGN CW90_DEG_FLIP
|
||||||
|
|
|
@ -51,15 +51,15 @@
|
||||||
#define BARO
|
#define BARO
|
||||||
#define USE_BARO_BMP280
|
#define USE_BARO_BMP280
|
||||||
|
|
||||||
#define MAG
|
//#define MAG
|
||||||
#define USE_MPU9250_MAG // Enables bypass configuration
|
//#define USE_MPU9250_MAG // Enables bypass configuration
|
||||||
#define USE_MAG_AK8975
|
//#define USE_MAG_AK8975
|
||||||
#define USE_MAG_HMC5883 // External
|
//#define USE_MAG_HMC5883 // External
|
||||||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
//#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||||
|
|
||||||
#define SONAR
|
//#define SONAR
|
||||||
#define SONAR_ECHO_PIN PB1
|
//#define SONAR_ECHO_PIN PB1
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
//#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define USB_IO
|
#define USB_IO
|
||||||
#define USB_CABLE_DETECTION
|
#define USB_CABLE_DETECTION
|
||||||
|
|
Loading…
Reference in New Issue