Fix F1 builds
This commit is contained in:
parent
b20e31f140
commit
740234c909
|
@ -54,6 +54,7 @@
|
|||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#ifndef USE_OSD_SLAVE
|
||||
|
|
|
@ -29,8 +29,8 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx_xn297.h"
|
||||
#include "drivers/rx/rx_nrf24l01.h"
|
||||
#include "drivers/rx/rx_xn297.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -31,8 +31,8 @@
|
|||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx_xn297.h"
|
||||
#include "drivers/rx/rx_nrf24l01.h"
|
||||
#include "drivers/rx/rx_xn297.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx/rx_nrf24l01.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx/rx_nrf24l01.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx/rx_nrf24l01.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -112,11 +112,13 @@ static int32_t currentMeterADCToCentiamps(const uint16_t src)
|
|||
return centiAmps; // Returns Centiamps to maintain compatability with the rest of the code
|
||||
}
|
||||
|
||||
#if defined(USE_ADC) || defined(USE_VIRTUAL_CURRENT_METER)
|
||||
static void updateCurrentmAhDrawnState(currentMeterMAhDrawnState_t *state, int32_t amperageLatest, int32_t lastUpdateAt)
|
||||
{
|
||||
state->mAhDrawnF = state->mAhDrawnF + (amperageLatest * lastUpdateAt / (100.0f * 1000 * 3600));
|
||||
state->mAhDrawn = state->mAhDrawnF;
|
||||
}
|
||||
#endif
|
||||
|
||||
//
|
||||
// ADC
|
||||
|
|
|
@ -23,20 +23,23 @@
|
|||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "io/serial.h"
|
||||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
|
||||
extern void spiPreInit(void); // XXX In fc/fc_init.c
|
||||
|
||||
void targetBusInit(void)
|
||||
{
|
||||
#if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
|
||||
spiPinConfigure();
|
||||
spiPinConfigure(spiPinConfig());
|
||||
spiPreInit();
|
||||
spiInit(SPIDEV_1);
|
||||
#endif
|
||||
|
||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||
serialRemovePort(SERIAL_PORT_USART3);
|
||||
i2cHardwareConfigure();
|
||||
i2cHardwareConfigure(i2cConfig());
|
||||
i2cInit(I2C_DEVICE);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -39,6 +39,9 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "pg/beeper_dev.h"
|
||||
#include "pg/flash.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
|
|
|
@ -24,13 +24,16 @@
|
|||
#include "drivers/bus_spi.h"
|
||||
#include "io/serial.h"
|
||||
#include "hardware_revision.h"
|
||||
#include "pg/bus_i2c.h"
|
||||
#include "pg/bus_spi.h"
|
||||
|
||||
|
||||
extern void spiPreInit(void); // XXX In fc/fc_init.c
|
||||
|
||||
void targetBusInit(void)
|
||||
{
|
||||
#ifdef USE_SPI
|
||||
spiPinConfigure();
|
||||
spiPinConfigure(spiPinConfig());
|
||||
spiPreInit();
|
||||
#ifdef USE_SPI_DEVICE_2
|
||||
spiInit(SPIDEV_2);
|
||||
|
@ -42,11 +45,11 @@ void targetBusInit(void)
|
|||
|
||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||
serialRemovePort(SERIAL_PORT_USART3);
|
||||
i2cHardwareConfigure();
|
||||
i2cHardwareConfigure(i2cConfig());
|
||||
i2cInit(I2C_DEVICE);
|
||||
}
|
||||
} else {
|
||||
i2cHardwareConfigure();
|
||||
i2cHardwareConfigure(i2cConfig());
|
||||
i2cInit(I2C_DEVICE);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue