mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Merge branch 'development' of https://github.com/borisbstyle/betaflight into build_parameterless_parallel
This commit is contained in:
commit
c7b8d94c7b
124 changed files with 2158 additions and 1829 deletions
34
Makefile
34
Makefile
|
@ -667,24 +667,36 @@ $(VALID_TARGETS):
|
|||
$(MAKE) binary hex TARGET=$@ && \
|
||||
echo "Building $@ succeeded."
|
||||
|
||||
## clean : clean up all temporary / machine-generated files
|
||||
|
||||
|
||||
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
|
||||
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
|
||||
|
||||
## clean : clean up temporary / machine-generated files
|
||||
clean:
|
||||
echo "Cleaning $(TARGET)"
|
||||
rm -f $(CLEAN_ARTIFACTS)
|
||||
rm -rf $(OBJECT_DIR)/$(TARGET)
|
||||
echo "Cleaning $(TARGET) succeeded."
|
||||
|
||||
## clean_test : clean up all temporary / machine-generated files (tests)
|
||||
## clean_test : clean up temporary / machine-generated files (tests)
|
||||
clean_test:
|
||||
cd src/test && $(MAKE) clean || true
|
||||
|
||||
## clean_all_targets : clean all valid target platforms
|
||||
clean_all:
|
||||
for clean_target in $(VALID_TARGETS); do \
|
||||
echo "" && \
|
||||
echo "Cleaning $$clean_target" && \
|
||||
$(MAKE) -j TARGET=$$clean_target clean || \
|
||||
break; \
|
||||
echo "Cleaning $$clean_target succeeded."; \
|
||||
done
|
||||
## clean_<TARGET> : clean up one specific target
|
||||
$(CLEAN_TARGETS) :
|
||||
$(MAKE) -j TARGET=$(subst clean_,,$@) clean
|
||||
|
||||
## <TARGET>_clean : clean up one specific target (alias for above)
|
||||
$(TARGETS_CLEAN) :
|
||||
$(MAKE) -j TARGET=$(subst _clean,,$@) clean
|
||||
|
||||
## clean_all : clean all valid targets
|
||||
clean_all:$(CLEAN_TARGETS)
|
||||
|
||||
## all_clean : clean all valid targets (alias for above)
|
||||
all_clean:$(TARGETS_CLEAN)
|
||||
|
||||
|
||||
flash_$(TARGET): $(TARGET_HEX)
|
||||
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
# Betaflight
|
||||
|
||||

|
||||

|
||||
|
||||
Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft.
|
||||
|
||||
|
|
|
@ -20,7 +20,10 @@ targets=("PUBLISHMETA=True" \
|
|||
"TARGET=ALIENFLIGHTF3" \
|
||||
"TARGET=DOGE" \
|
||||
"TARGET=SINGULARITY" \
|
||||
"TARGET=SIRINFPV")
|
||||
"TARGET=SIRINFPV" \
|
||||
"TARGET=X_RACERSPI")
|
||||
|
||||
|
||||
|
||||
#fake a travis build environment
|
||||
export TRAVIS_BUILD_NUMBER=$(date +%s)
|
||||
|
@ -30,9 +33,9 @@ export TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/simulated}
|
|||
for target in "${targets[@]}"
|
||||
do
|
||||
unset RUNTESTS PUBLISHMETA TARGET
|
||||
echo
|
||||
echo
|
||||
echo "BUILDING '$target'"
|
||||
echo
|
||||
echo
|
||||
echo "BUILDING '$target'"
|
||||
eval "export $target"
|
||||
make -f Makefile clean
|
||||
./.travis.sh
|
||||
|
|
|
@ -228,8 +228,8 @@ enum EP_BUF_NUM
|
|||
/* GetDADDR */
|
||||
#define _GetDADDR() ((__IO uint16_t) *DADDR)
|
||||
|
||||
/* GetBTABLE */
|
||||
#define _GetBTABLE() ((__IO uint16_t) *BTABLE)
|
||||
/* GetBTABLE ; clear low-order bits explicitly to avoid problems in gcc 5.x */
|
||||
#define _GetBTABLE() (((__IO uint16_t) *BTABLE) & ~0x07)
|
||||
|
||||
/* SetENDPOINT */
|
||||
#define _SetENDPOINT(bEpNum,wRegValue) (*(EP0REG + bEpNum)= \
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -178,7 +180,7 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
|||
accelerometerTrims->values.yaw = 0;
|
||||
}
|
||||
|
||||
static void resetPidProfile(pidProfile_t *pidProfile)
|
||||
void resetPidProfile(pidProfile_t *pidProfile)
|
||||
{
|
||||
|
||||
#if (defined(STM32F10X))
|
||||
|
@ -193,7 +195,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
pidProfile->P8[PITCH] = 50;
|
||||
pidProfile->I8[PITCH] = 40;
|
||||
pidProfile->D8[PITCH] = 18;
|
||||
pidProfile->P8[YAW] = 90;
|
||||
pidProfile->P8[YAW] = 80;
|
||||
pidProfile->I8[YAW] = 45;
|
||||
pidProfile->D8[YAW] = 20;
|
||||
pidProfile->P8[PIDALT] = 50;
|
||||
|
@ -218,10 +220,10 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
|
||||
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
|
||||
pidProfile->yaw_lpf_hz = 80;
|
||||
pidProfile->rollPitchItermIgnoreRate = 200;
|
||||
pidProfile->rollPitchItermIgnoreRate = 180;
|
||||
pidProfile->yawItermIgnoreRate = 35;
|
||||
pidProfile->dterm_lpf_hz = 50; // filtering ON by default
|
||||
pidProfile->deltaMethod = DELTA_FROM_ERROR;
|
||||
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
|
||||
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
|
||||
pidProfile->dynamic_pid = 1;
|
||||
|
||||
#ifdef GTUNE
|
||||
|
@ -397,7 +399,7 @@ uint8_t getCurrentControlRateProfile(void)
|
|||
static void setControlRateProfile(uint8_t profileIndex)
|
||||
{
|
||||
currentControlRateProfileIndex = profileIndex;
|
||||
masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
|
||||
masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
|
||||
currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
|
||||
}
|
||||
|
||||
|
@ -536,10 +538,10 @@ static void resetConf(void)
|
|||
|
||||
#ifdef GPS
|
||||
// gps/nav stuff
|
||||
masterConfig.gpsConfig.provider = GPS_NMEA;
|
||||
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
||||
masterConfig.gpsConfig.provider = GPS_NMEA;
|
||||
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
||||
masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
|
||||
masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||
masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
|
||||
#endif
|
||||
|
||||
resetSerialConfig(&masterConfig.serialConfig);
|
||||
|
@ -615,14 +617,14 @@ static void resetConf(void)
|
|||
masterConfig.vtx_mhz = 5740; //F0
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3
|
||||
masterConfig.blackbox_device = 1;
|
||||
#ifdef TRANSPONDER
|
||||
static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware
|
||||
|
||||
memcpy(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||
featureSet(FEATURE_BLACKBOX);
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||
|
@ -630,13 +632,14 @@ static void resetConf(void)
|
|||
featureSet(FEATURE_BLACKBOX);
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD;
|
||||
#else
|
||||
masterConfig.blackbox_device = 0;
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
#endif
|
||||
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
#endif
|
||||
|
||||
#endif // BLACKBOX
|
||||
|
||||
// alternative defaults settings for COLIBRI RACE targets
|
||||
#if defined(COLIBRI_RACE)
|
||||
masterConfig.escAndServoConfig.minthrottle = 1025;
|
||||
|
@ -651,20 +654,21 @@ static void resetConf(void)
|
|||
|
||||
#if defined(ALIENFLIGHT)
|
||||
featureClear(FEATURE_ONESHOT125);
|
||||
#ifdef ALIENFLIGHTF3
|
||||
#ifdef ALIENFLIGHTF1
|
||||
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
|
||||
#else
|
||||
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
#endif
|
||||
#ifdef ALIENFLIGHTF3
|
||||
masterConfig.batteryConfig.vbatscale = 20;
|
||||
masterConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||
#else
|
||||
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
|
||||
#endif
|
||||
masterConfig.rxConfig.serialrx_provider = 1;
|
||||
masterConfig.rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048;
|
||||
masterConfig.rxConfig.spektrum_sat_bind = 5;
|
||||
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
masterConfig.escAndServoConfig.minthrottle = 1000;
|
||||
masterConfig.escAndServoConfig.maxthrottle = 2000;
|
||||
masterConfig.motor_pwm_rate = 32000;
|
||||
currentProfile->pidProfile.pidController = 2;
|
||||
masterConfig.failsafeConfig.failsafe_delay = 2;
|
||||
masterConfig.failsafeConfig.failsafe_off_delay = 0;
|
||||
currentControlRateProfile->rates[FD_PITCH] = 40;
|
||||
|
@ -684,10 +688,6 @@ static void resetConf(void)
|
|||
|
||||
#if defined(SINGULARITY)
|
||||
// alternative defaults settings for SINGULARITY target
|
||||
masterConfig.blackbox_device = 1;
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
|
||||
masterConfig.batteryConfig.vbatscale = 77;
|
||||
|
||||
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||
|
@ -1046,7 +1046,8 @@ void changeProfile(uint8_t profileIndex)
|
|||
beeperConfirmationBeeps(profileIndex + 1);
|
||||
}
|
||||
|
||||
void changeControlRateProfile(uint8_t profileIndex) {
|
||||
void changeControlRateProfile(uint8_t profileIndex)
|
||||
{
|
||||
if (profileIndex > MAX_RATEPROFILES) {
|
||||
profileIndex = MAX_RATEPROFILES - 1;
|
||||
}
|
||||
|
@ -1054,17 +1055,6 @@ void changeControlRateProfile(uint8_t profileIndex) {
|
|||
activateControlRateConfig();
|
||||
}
|
||||
|
||||
void handleOneshotFeatureChangeOnRestart(void)
|
||||
{
|
||||
// Shutdown PWM on all motors prior to soft restart
|
||||
StopPwmAllMotors();
|
||||
delay(50);
|
||||
// Apply additional delay when OneShot125 feature changed from on to off state
|
||||
if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
|
||||
delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
|
||||
}
|
||||
}
|
||||
|
||||
void latchActiveFeatures()
|
||||
{
|
||||
activeFeaturesLatch = masterConfig.enabledFeatures;
|
||||
|
|
|
@ -50,7 +50,6 @@ typedef enum {
|
|||
FEATURE_VTX = 1 << 25,
|
||||
} features_e;
|
||||
|
||||
void handleOneshotFeatureChangeOnRestart(void);
|
||||
void latchActiveFeatures(void);
|
||||
bool featureConfigured(uint32_t mask);
|
||||
bool feature(uint32_t mask);
|
||||
|
|
|
@ -40,7 +40,7 @@ bool bma280Detect(acc_t *acc)
|
|||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||
if (!ack || sig != 0xFB)
|
||||
return false;
|
||||
|
||||
|
@ -51,8 +51,8 @@ bool bma280Detect(acc_t *acc)
|
|||
|
||||
static void bma280Init(acc_t *acc)
|
||||
{
|
||||
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
|
||||
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW
|
||||
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
|
||||
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW
|
||||
|
||||
acc->acc_1G = 512 * 8;
|
||||
}
|
||||
|
@ -61,7 +61,7 @@ static bool bma280Read(int16_t *accelData)
|
|||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
if (!i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) {
|
||||
if (!i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -63,7 +63,7 @@ bool l3g4200dDetect(gyro_t *gyro)
|
|||
|
||||
delay(25);
|
||||
|
||||
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
|
||||
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
|
||||
if (deviceid != L3G4200D_ID)
|
||||
return false;
|
||||
|
||||
|
@ -100,12 +100,12 @@ static void l3g4200dInit(uint8_t lpf)
|
|||
|
||||
delay(100);
|
||||
|
||||
ack = i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS);
|
||||
ack = i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS);
|
||||
if (!ack)
|
||||
failureMode(FAILURE_ACC_INIT);
|
||||
|
||||
delay(5);
|
||||
i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter);
|
||||
i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter);
|
||||
}
|
||||
|
||||
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
||||
|
@ -113,7 +113,7 @@ static bool l3g4200dRead(int16_t *gyroADC)
|
|||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
if (!i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) {
|
||||
if (!i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -62,7 +62,7 @@
|
|||
|
||||
#define BLOCK_DATA_UPDATE_CONTINUOUS ((uint8_t)0x00)
|
||||
|
||||
#define BLE_MSB ((uint8_t)0x40)
|
||||
#define BLE_MSB ((uint8_t)0x40)
|
||||
|
||||
#define BOOT ((uint8_t)0x80)
|
||||
|
||||
|
@ -81,7 +81,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
|
|||
|
||||
DISABLE_L3GD20;
|
||||
|
||||
spiSetDivisor(L3GD20_SPI, SPI_9MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(L3GD20_SPI, SPI_CLOCK_STANDARD);
|
||||
}
|
||||
|
||||
void l3gd20GyroInit(uint8_t lpf)
|
||||
|
|
|
@ -115,15 +115,15 @@ int32_t accelSummedSamples500Hz[3];
|
|||
|
||||
void lsm303dlhcAccInit(acc_t *acc)
|
||||
{
|
||||
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
|
||||
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
|
||||
|
||||
delay(100);
|
||||
|
||||
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
|
||||
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
|
||||
|
||||
delay(10);
|
||||
|
||||
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G);
|
||||
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G);
|
||||
|
||||
delay(100);
|
||||
|
||||
|
|
|
@ -89,7 +89,7 @@ bool mma8452Detect(acc_t *acc)
|
|||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||
return false;
|
||||
|
||||
|
@ -109,9 +109,9 @@ static inline void mma8451ConfigureInterrupt(void)
|
|||
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||
#endif
|
||||
|
||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
|
||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
|
||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
|
||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
|
||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
|
||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
|
||||
}
|
||||
|
||||
static void mma8452Init(acc_t *acc)
|
||||
|
|
|
@ -228,43 +228,43 @@ void mpuIntExtiHandler(extiCallbackRec_t *cb)
|
|||
|
||||
void mpuIntExtiInit(void)
|
||||
{
|
||||
static bool mpuExtiInitDone = false;
|
||||
static bool mpuExtiInitDone = false;
|
||||
|
||||
if (mpuExtiInitDone || !mpuIntExtiConfig) {
|
||||
return;
|
||||
}
|
||||
if (mpuExtiInitDone || !mpuIntExtiConfig) {
|
||||
return;
|
||||
}
|
||||
|
||||
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
|
||||
|
||||
IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag);
|
||||
|
||||
IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag);
|
||||
|
||||
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
|
||||
uint8_t status = IORead(mpuIntIO);
|
||||
if (status) {
|
||||
return;
|
||||
}
|
||||
uint8_t status = IORead(mpuIntIO);
|
||||
if (status) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
|
||||
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||
IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
|
||||
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||
|
||||
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
||||
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
|
||||
EXTIEnable(mpuIntIO, true);
|
||||
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
||||
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
|
||||
EXTIEnable(mpuIntIO, true);
|
||||
#endif
|
||||
|
||||
mpuExtiInitDone = true;
|
||||
mpuExtiInitDone = true;
|
||||
}
|
||||
|
||||
static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data)
|
||||
{
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, length, data);
|
||||
bool ack = i2cRead(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, length, data);
|
||||
return ack;
|
||||
}
|
||||
|
||||
static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data)
|
||||
{
|
||||
bool ack = i2cWrite(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, data);
|
||||
bool ack = i2cWrite(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, data);
|
||||
return ack;
|
||||
}
|
||||
|
||||
|
|
|
@ -120,12 +120,12 @@ typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data);
|
|||
typedef void(*mpuResetFuncPtr)(void);
|
||||
|
||||
typedef struct mpuConfiguration_s {
|
||||
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
|
||||
mpuReadRegisterFunc read;
|
||||
mpuWriteRegisterFunc write;
|
||||
mpuReadRegisterFunc slowread;
|
||||
mpuWriteRegisterFunc verifywrite;
|
||||
mpuResetFuncPtr reset;
|
||||
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
|
||||
mpuReadRegisterFunc read;
|
||||
mpuWriteRegisterFunc write;
|
||||
mpuReadRegisterFunc slowread;
|
||||
mpuWriteRegisterFunc verifywrite;
|
||||
mpuResetFuncPtr reset;
|
||||
} mpuConfiguration_t;
|
||||
|
||||
extern mpuConfiguration_t mpuConfiguration;
|
||||
|
|
|
@ -49,12 +49,12 @@ static bool mpuSpi6000InitDone = false;
|
|||
|
||||
|
||||
// Bits
|
||||
#define BIT_SLEEP 0x40
|
||||
#define BIT_H_RESET 0x80
|
||||
#define BITS_CLKSEL 0x07
|
||||
#define MPU_CLK_SEL_PLLGYROX 0x01
|
||||
#define MPU_CLK_SEL_PLLGYROZ 0x03
|
||||
#define MPU_EXT_SYNC_GYROX 0x02
|
||||
#define BIT_SLEEP 0x40
|
||||
#define BIT_H_RESET 0x80
|
||||
#define BITS_CLKSEL 0x07
|
||||
#define MPU_CLK_SEL_PLLGYROX 0x01
|
||||
#define MPU_CLK_SEL_PLLGYROZ 0x03
|
||||
#define MPU_EXT_SYNC_GYROX 0x02
|
||||
#define BITS_FS_250DPS 0x00
|
||||
#define BITS_FS_500DPS 0x08
|
||||
#define BITS_FS_1000DPS 0x10
|
||||
|
@ -74,9 +74,9 @@ static bool mpuSpi6000InitDone = false;
|
|||
#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
|
||||
#define BITS_DLPF_CFG_MASK 0x07
|
||||
#define BIT_INT_ANYRD_2CLEAR 0x10
|
||||
#define BIT_RAW_RDY_EN 0x01
|
||||
#define BIT_RAW_RDY_EN 0x01
|
||||
#define BIT_I2C_IF_DIS 0x10
|
||||
#define BIT_INT_STATUS_DATA 0x01
|
||||
#define BIT_INT_STATUS_DATA 0x01
|
||||
#define BIT_GYRO 3
|
||||
#define BIT_ACC 2
|
||||
#define BIT_TEMP 1
|
||||
|
@ -128,13 +128,13 @@ void mpu6000SpiGyroInit(uint8_t lpf)
|
|||
|
||||
mpu6000AccAndGyroInit();
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
||||
|
||||
// Accel and Gyro DLPF Setting
|
||||
mpu6000WriteRegister(MPU6000_CONFIG, lpf);
|
||||
delayMicroseconds(1);
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); // 18 MHz SPI clock
|
||||
|
||||
int16_t data[3];
|
||||
mpuGyroRead(data);
|
||||
|
@ -162,7 +162,7 @@ bool mpu6000SpiDetect(void)
|
|||
IOInit(mpuSpi6000CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
||||
|
||||
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
||||
|
||||
|
@ -209,7 +209,7 @@ static void mpu6000AccAndGyroInit(void) {
|
|||
return;
|
||||
}
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
||||
|
||||
// Device Reset
|
||||
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
||||
|
@ -251,7 +251,7 @@ static void mpu6000AccAndGyroInit(void) {
|
|||
delayMicroseconds(15);
|
||||
#endif
|
||||
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
|
||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||
delayMicroseconds(1);
|
||||
|
||||
mpuSpi6000InitDone = true;
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define MPU6000_CONFIG 0x1A
|
||||
#define MPU6000_CONFIG 0x1A
|
||||
|
||||
#define BITS_DLPF_CFG_256HZ 0x00
|
||||
#define BITS_DLPF_CFG_188HZ 0x01
|
||||
|
|
|
@ -72,11 +72,7 @@ static void mpu6500SpiInit(void)
|
|||
IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
#if defined(STM32F4)
|
||||
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_SLOW_CLOCK);
|
||||
#else
|
||||
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_STANDARD_CLOCK);
|
||||
#endif
|
||||
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
|
|
@ -55,7 +55,8 @@ static IO_t mpuSpi9250CsPin = IO_NONE;
|
|||
#define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin)
|
||||
#define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin)
|
||||
|
||||
void mpu9250ResetGyro(void) {
|
||||
void mpu9250ResetGyro(void)
|
||||
{
|
||||
// Device Reset
|
||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
||||
delay(150);
|
||||
|
@ -63,7 +64,7 @@ void mpu9250ResetGyro(void) {
|
|||
|
||||
bool mpu9250WriteRegister(uint8_t reg, uint8_t data)
|
||||
{
|
||||
ENABLE_MPU9250;
|
||||
ENABLE_MPU9250;
|
||||
delayMicroseconds(1);
|
||||
spiTransferByte(MPU9250_SPI_INSTANCE, reg);
|
||||
spiTransferByte(MPU9250_SPI_INSTANCE, data);
|
||||
|
@ -75,7 +76,7 @@ bool mpu9250WriteRegister(uint8_t reg, uint8_t data)
|
|||
|
||||
bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
||||
{
|
||||
ENABLE_MPU9250;
|
||||
ENABLE_MPU9250;
|
||||
spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction
|
||||
spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length);
|
||||
DISABLE_MPU9250;
|
||||
|
@ -85,7 +86,7 @@ bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
|||
|
||||
bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
||||
{
|
||||
ENABLE_MPU9250;
|
||||
ENABLE_MPU9250;
|
||||
delayMicroseconds(1);
|
||||
spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction
|
||||
spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length);
|
||||
|
@ -97,7 +98,7 @@ bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
|||
|
||||
void mpu9250SpiGyroInit(uint8_t lpf)
|
||||
{
|
||||
(void)(lpf);
|
||||
(void)(lpf);
|
||||
|
||||
mpuIntExtiInit();
|
||||
|
||||
|
@ -105,7 +106,7 @@ void mpu9250SpiGyroInit(uint8_t lpf)
|
|||
|
||||
spiResetErrorCounter(MPU9250_SPI_INSTANCE);
|
||||
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, 5); //high speed now that we don't need to write to the slow registers
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers
|
||||
|
||||
int16_t data[3];
|
||||
mpuGyroRead(data);
|
||||
|
@ -123,60 +124,61 @@ void mpu9250SpiAccInit(acc_t *acc)
|
|||
acc->acc_1G = 512 * 8;
|
||||
}
|
||||
|
||||
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data)
|
||||
{
|
||||
uint8_t in;
|
||||
uint8_t attemptsRemaining = 20;
|
||||
|
||||
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) {
|
||||
|
||||
uint8_t in;
|
||||
uint8_t attemptsRemaining = 20;
|
||||
|
||||
mpu9250WriteRegister(reg, data);
|
||||
delayMicroseconds(100);
|
||||
mpu9250WriteRegister(reg, data);
|
||||
delayMicroseconds(100);
|
||||
|
||||
do {
|
||||
mpu9250SlowReadRegister(reg, 1, &in);
|
||||
if (in == data) {
|
||||
return true;
|
||||
} else {
|
||||
debug[3]++;
|
||||
mpu9250WriteRegister(reg, data);
|
||||
delayMicroseconds(100);
|
||||
}
|
||||
mpu9250SlowReadRegister(reg, 1, &in);
|
||||
if (in == data) {
|
||||
return true;
|
||||
} else {
|
||||
debug[3]++;
|
||||
mpu9250WriteRegister(reg, data);
|
||||
delayMicroseconds(100);
|
||||
}
|
||||
} while (attemptsRemaining--);
|
||||
return false;
|
||||
}
|
||||
|
||||
static void mpu9250AccAndGyroInit(uint8_t lpf) {
|
||||
|
||||
if (mpuSpi9250InitDone) {
|
||||
return;
|
||||
}
|
||||
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed for writing to slow registers
|
||||
|
||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
||||
delay(50);
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11
|
||||
|
||||
if (lpf == 4) {
|
||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 1); //1KHz, 184DLPF
|
||||
} else if (lpf < 4) {
|
||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 7); //8KHz, 3600DLPF
|
||||
} else if (lpf > 4) {
|
||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 0); //8KHz, 250DLPF
|
||||
if (mpuSpi9250InitDone) {
|
||||
return;
|
||||
}
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
|
||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
||||
delay(50);
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11
|
||||
|
||||
if (lpf == 4) {
|
||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 1); //1KHz, 184DLPF
|
||||
} else if (lpf < 4) {
|
||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 7); //8KHz, 3600DLPF
|
||||
} else if (lpf > 4) {
|
||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 0); //8KHz, 250DLPF
|
||||
}
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops
|
||||
|
||||
verifympu9250WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||
verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
|
||||
|
||||
#if defined(USE_MPU_DATA_READY_SIGNAL)
|
||||
verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
|
||||
verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
|
||||
#endif
|
||||
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||
|
||||
mpuSpi9250InitDone = true; //init done
|
||||
}
|
||||
|
||||
|
@ -189,10 +191,10 @@ bool mpu9250SpiDetect(void)
|
|||
#ifdef MPU9250_CS_PIN
|
||||
mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN));
|
||||
#endif
|
||||
IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
|
||||
IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
|
||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
||||
|
||||
do {
|
||||
|
@ -207,6 +209,8 @@ bool mpu9250SpiDetect(void)
|
|||
}
|
||||
} while (attemptsRemaining--);
|
||||
|
||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define mpu9250_CONFIG 0x1A
|
||||
#define mpu9250_CONFIG 0x1A
|
||||
|
||||
/* We should probably use these. :)
|
||||
#define BITS_DLPF_CFG_256HZ 0x00
|
||||
|
|
|
@ -33,6 +33,14 @@
|
|||
adc_config_t adcConfig[ADC_CHANNEL_COUNT];
|
||||
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
||||
|
||||
uint8_t adcChannelByTag(ioTag_t ioTag)
|
||||
{
|
||||
for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) {
|
||||
if (ioTag == adcTagMap[i].tag)
|
||||
return adcTagMap[i].channel;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint16_t adcGetChannel(uint8_t channel)
|
||||
{
|
||||
|
|
|
@ -17,5 +17,52 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#if defined(STM32F4)
|
||||
#define ADC_TAG_MAP_COUNT 16
|
||||
#elif defined(STM32F3)
|
||||
#define ADC_TAG_MAP_COUNT 39
|
||||
#else
|
||||
#define ADC_TAG_MAP_COUNT 10
|
||||
#endif
|
||||
|
||||
typedef enum ADCDevice {
|
||||
ADCINVALID = -1,
|
||||
ADCDEV_1 = 0,
|
||||
#if defined(STM32F3)
|
||||
ADCDEV_2,
|
||||
ADCDEV_MAX = ADCDEV_2,
|
||||
#elif defined(STM32F4)
|
||||
ADCDEV_2,
|
||||
ADCDEV_3,
|
||||
ADCDEV_MAX = ADCDEV_3,
|
||||
#else
|
||||
ADCDEV_MAX = ADCDEV_1,
|
||||
#endif
|
||||
} ADCDevice;
|
||||
|
||||
typedef struct adcTagMap_s {
|
||||
ioTag_t tag;
|
||||
uint8_t channel;
|
||||
} adcTagMap_t;
|
||||
|
||||
typedef struct adcDevice_s {
|
||||
ADC_TypeDef* ADCx;
|
||||
rccPeriphTag_t rccADC;
|
||||
rccPeriphTag_t rccDMA;
|
||||
#if defined(STM32F4)
|
||||
DMA_Stream_TypeDef* DMAy_Streamx;
|
||||
uint32_t channel;
|
||||
#else
|
||||
DMA_Channel_TypeDef* DMAy_Channelx;
|
||||
#endif
|
||||
} adcDevice_t;
|
||||
|
||||
extern const adcDevice_t adcHardware[];
|
||||
extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
|
||||
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
|
||||
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
||||
|
||||
uint8_t adcChannelByTag(ioTag_t ioTag);
|
|
@ -29,17 +29,44 @@
|
|||
|
||||
#include "sensor.h"
|
||||
#include "accgyro.h"
|
||||
|
||||
#include "adc.h"
|
||||
#include "adc_impl.h"
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#ifndef ADC_INSTANCE
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_ABP2_PERIPHERAL RCC_APB2Periph_ADC1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||
#define ADC_INSTANCE ADC1
|
||||
#endif
|
||||
|
||||
const adcDevice_t adcHardware[] = {
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }
|
||||
};
|
||||
|
||||
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||
{
|
||||
if (instance == ADC1)
|
||||
return ADCDEV_1;
|
||||
|
||||
/* TODO -- ADC2 available on large 10x devices.
|
||||
if (instance == ADC2)
|
||||
return ADCDEV_2;
|
||||
*/
|
||||
return ADCINVALID;
|
||||
}
|
||||
|
||||
const adcTagMap_t adcTagMap[] = {
|
||||
{ DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA3, ADC_Channel_3 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA4, ADC_Channel_4 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA5, ADC_Channel_5 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12
|
||||
{ DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12
|
||||
{ DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12
|
||||
{ DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12
|
||||
};
|
||||
|
||||
// Driver for STM32F103CB onboard ADC
|
||||
//
|
||||
// Naze32
|
||||
|
@ -50,77 +77,78 @@
|
|||
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
||||
//
|
||||
|
||||
|
||||
void adcInit(drv_adc_config_t *init)
|
||||
{
|
||||
#if defined(CJMCU) || defined(CC3D)
|
||||
|
||||
#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
|
||||
UNUSED(init);
|
||||
#endif
|
||||
|
||||
|
||||
uint8_t i;
|
||||
uint8_t configuredAdcChannels = 0;
|
||||
|
||||
memset(&adcConfig, 0, sizeof(adcConfig));
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
|
||||
|
||||
#ifdef VBAT_ADC_GPIO
|
||||
#ifdef VBAT_ADC_PIN
|
||||
if (init->enableVBat) {
|
||||
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
|
||||
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
|
||||
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
|
||||
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
|
||||
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN));
|
||||
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_BATTERY].enabled = true;
|
||||
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef RSSI_ADC_GPIO
|
||||
#ifdef RSSI_ADC_PIN
|
||||
if (init->enableRSSI) {
|
||||
GPIO_InitStructure.GPIO_Pin = RSSI_ADC_GPIO_PIN;
|
||||
GPIO_Init(RSSI_ADC_GPIO, &GPIO_InitStructure);
|
||||
adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
|
||||
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
|
||||
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN));
|
||||
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_RSSI].enabled = true;
|
||||
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef EXTERNAL1_ADC_GPIO
|
||||
#ifdef EXTERNAL1_ADC_PIN
|
||||
if (init->enableExternal1) {
|
||||
GPIO_InitStructure.GPIO_Pin = EXTERNAL1_ADC_GPIO_PIN;
|
||||
GPIO_Init(EXTERNAL1_ADC_GPIO, &GPIO_InitStructure);
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
|
||||
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN));
|
||||
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_EXTERNAL1].enabled = true;
|
||||
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CURRENT_METER_ADC_GPIO
|
||||
#ifdef CURRENT_METER_ADC_PIN
|
||||
if (init->enableCurrentMeter) {
|
||||
GPIO_InitStructure.GPIO_Pin = CURRENT_METER_ADC_GPIO_PIN;
|
||||
GPIO_Init(CURRENT_METER_ADC_GPIO, &GPIO_InitStructure);
|
||||
adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
|
||||
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0));
|
||||
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN));
|
||||
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_CURRENT].enabled = true;
|
||||
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
#endif
|
||||
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
if (device == ADCINVALID)
|
||||
return;
|
||||
|
||||
adcDevice_t adc = adcHardware[device];
|
||||
|
||||
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
|
||||
RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(ADC_ABP2_PERIPHERAL, ENABLE);
|
||||
|
||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
||||
|
||||
// FIXME ADC driver assumes all the GPIO was already placed in 'AIN' mode
|
||||
|
||||
DMA_DeInit(ADC_DMA_CHANNEL);
|
||||
DMA_DeInit(adc.DMAy_Channelx);
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR;
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
|
||||
|
@ -131,8 +159,8 @@ void adcInit(drv_adc_config_t *init)
|
|||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure);
|
||||
DMA_Cmd(ADC_DMA_CHANNEL, ENABLE);
|
||||
DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure);
|
||||
DMA_Cmd(adc.DMAy_Channelx, ENABLE);
|
||||
|
||||
ADC_InitTypeDef ADC_InitStructure;
|
||||
ADC_StructInit(&ADC_InitStructure);
|
||||
|
@ -142,23 +170,23 @@ void adcInit(drv_adc_config_t *init)
|
|||
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
|
||||
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
|
||||
ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels;
|
||||
ADC_Init(ADC_INSTANCE, &ADC_InitStructure);
|
||||
ADC_Init(adc.ADCx, &ADC_InitStructure);
|
||||
|
||||
uint8_t rank = 1;
|
||||
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||
if (!adcConfig[i].enabled) {
|
||||
continue;
|
||||
}
|
||||
ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
||||
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
||||
}
|
||||
|
||||
ADC_DMACmd(ADC_INSTANCE, ENABLE);
|
||||
ADC_Cmd(ADC_INSTANCE, ENABLE);
|
||||
ADC_DMACmd(adc.ADCx, ENABLE);
|
||||
ADC_Cmd(adc.ADCx, ENABLE);
|
||||
|
||||
ADC_ResetCalibration(ADC_INSTANCE);
|
||||
while(ADC_GetResetCalibrationStatus(ADC_INSTANCE));
|
||||
ADC_StartCalibration(ADC_INSTANCE);
|
||||
while(ADC_GetCalibrationStatus(ADC_INSTANCE));
|
||||
ADC_ResetCalibration(adc.ADCx);
|
||||
while (ADC_GetResetCalibrationStatus(adc.ADCx));
|
||||
ADC_StartCalibration(adc.ADCx);
|
||||
while (ADC_GetCalibrationStatus(adc.ADCx));
|
||||
|
||||
ADC_SoftwareStartConvCmd(ADC_INSTANCE, ENABLE);
|
||||
ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE);
|
||||
}
|
||||
|
|
|
@ -29,35 +29,88 @@
|
|||
|
||||
#include "adc.h"
|
||||
#include "adc_impl.h"
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#ifndef ADC_INSTANCE
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||
#endif
|
||||
|
||||
const adcDevice_t adcHardware[] = {
|
||||
{ .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 },
|
||||
{ .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 }
|
||||
};
|
||||
|
||||
const adcTagMap_t adcTagMap[] = {
|
||||
{ DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1
|
||||
{ DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1
|
||||
{ DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1
|
||||
{ DEFIO_TAG_E__PA3, ADC_Channel_4 }, // ADC1
|
||||
{ DEFIO_TAG_E__PA4, ADC_Channel_1 }, // ADC2
|
||||
{ DEFIO_TAG_E__PA5, ADC_Channel_2 }, // ADC2
|
||||
{ DEFIO_TAG_E__PA6, ADC_Channel_3 }, // ADC2
|
||||
{ DEFIO_TAG_E__PA7, ADC_Channel_4 }, // ADC2
|
||||
{ DEFIO_TAG_E__PB0, ADC_Channel_12 }, // ADC3
|
||||
{ DEFIO_TAG_E__PB1, ADC_Channel_1 }, // ADC3
|
||||
{ DEFIO_TAG_E__PB2, ADC_Channel_12 }, // ADC2
|
||||
{ DEFIO_TAG_E__PB12, ADC_Channel_3 }, // ADC4
|
||||
{ DEFIO_TAG_E__PB13, ADC_Channel_5 }, // ADC3
|
||||
{ DEFIO_TAG_E__PB14, ADC_Channel_4 }, // ADC4
|
||||
{ DEFIO_TAG_E__PB15, ADC_Channel_5 }, // ADC4
|
||||
{ DEFIO_TAG_E__PC0, ADC_Channel_6 }, // ADC12
|
||||
{ DEFIO_TAG_E__PC1, ADC_Channel_7 }, // ADC12
|
||||
{ DEFIO_TAG_E__PC2, ADC_Channel_8 }, // ADC12
|
||||
{ DEFIO_TAG_E__PC3, ADC_Channel_9 }, // ADC12
|
||||
{ DEFIO_TAG_E__PC4, ADC_Channel_5 }, // ADC2
|
||||
{ DEFIO_TAG_E__PC5, ADC_Channel_11 }, // ADC2
|
||||
{ DEFIO_TAG_E__PD8, ADC_Channel_12 }, // ADC4
|
||||
{ DEFIO_TAG_E__PD9, ADC_Channel_13 }, // ADC4
|
||||
{ DEFIO_TAG_E__PD10, ADC_Channel_7 }, // ADC34
|
||||
{ DEFIO_TAG_E__PD11, ADC_Channel_8 }, // ADC34
|
||||
{ DEFIO_TAG_E__PD12, ADC_Channel_9 }, // ADC34
|
||||
{ DEFIO_TAG_E__PD13, ADC_Channel_10 }, // ADC34
|
||||
{ DEFIO_TAG_E__PD14, ADC_Channel_11 }, // ADC34
|
||||
{ DEFIO_TAG_E__PE7, ADC_Channel_13 }, // ADC3
|
||||
{ DEFIO_TAG_E__PE8, ADC_Channel_6 }, // ADC34
|
||||
{ DEFIO_TAG_E__PE9, ADC_Channel_2 }, // ADC3
|
||||
{ DEFIO_TAG_E__PE10, ADC_Channel_14 }, // ADC3
|
||||
{ DEFIO_TAG_E__PE11, ADC_Channel_15 }, // ADC3
|
||||
{ DEFIO_TAG_E__PE12, ADC_Channel_16 }, // ADC3
|
||||
{ DEFIO_TAG_E__PE13, ADC_Channel_3 }, // ADC3
|
||||
{ DEFIO_TAG_E__PE14, ADC_Channel_1 }, // ADC4
|
||||
{ DEFIO_TAG_E__PE15, ADC_Channel_2 }, // ADC4
|
||||
{ DEFIO_TAG_E__PF2, ADC_Channel_10 }, // ADC12
|
||||
{ DEFIO_TAG_E__PF4, ADC_Channel_5 }, // ADC1
|
||||
};
|
||||
|
||||
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||
{
|
||||
if (instance == ADC1)
|
||||
return ADCDEV_1;
|
||||
|
||||
if (instance == ADC2)
|
||||
return ADCDEV_2;
|
||||
|
||||
return ADCINVALID;
|
||||
}
|
||||
|
||||
void adcInit(drv_adc_config_t *init)
|
||||
{
|
||||
UNUSED(init);
|
||||
ADC_InitTypeDef ADC_InitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
uint8_t i;
|
||||
uint8_t adcChannelCount = 0;
|
||||
|
||||
memset(&adcConfig, 0, sizeof(adcConfig));
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
|
||||
|
||||
#ifdef VBAT_ADC_GPIO
|
||||
#ifdef VBAT_ADC_PIN
|
||||
if (init->enableVBat) {
|
||||
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
|
||||
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
|
||||
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
|
||||
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
|
||||
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN));
|
||||
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount;
|
||||
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5;
|
||||
adcConfig[ADC_BATTERY].enabled = true;
|
||||
|
@ -65,12 +118,12 @@ void adcInit(drv_adc_config_t *init)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef RSSI_ADC_GPIO
|
||||
#ifdef RSSI_ADC_PIN
|
||||
if (init->enableRSSI) {
|
||||
GPIO_InitStructure.GPIO_Pin = RSSI_ADC_GPIO_PIN;
|
||||
GPIO_Init(RSSI_ADC_GPIO, &GPIO_InitStructure);
|
||||
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
|
||||
adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
|
||||
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN));
|
||||
adcConfig[ADC_RSSI].dmaIndex = adcChannelCount;
|
||||
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5;
|
||||
adcConfig[ADC_RSSI].enabled = true;
|
||||
|
@ -80,10 +133,10 @@ void adcInit(drv_adc_config_t *init)
|
|||
|
||||
#ifdef CURRENT_METER_ADC_GPIO
|
||||
if (init->enableCurrentMeter) {
|
||||
GPIO_InitStructure.GPIO_Pin = CURRENT_METER_ADC_GPIO_PIN;
|
||||
GPIO_Init(CURRENT_METER_ADC_GPIO, &GPIO_InitStructure);
|
||||
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
|
||||
adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
|
||||
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN));
|
||||
adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount;
|
||||
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_601Cycles5;
|
||||
adcConfig[ADC_CURRENT].enabled = true;
|
||||
|
@ -93,10 +146,10 @@ void adcInit(drv_adc_config_t *init)
|
|||
|
||||
#ifdef EXTERNAL1_ADC_GPIO
|
||||
if (init->enableExternal1) {
|
||||
GPIO_InitStructure.GPIO_Pin = EXTERNAL1_ADC_GPIO_PIN;
|
||||
GPIO_Init(EXTERNAL1_ADC_GPIO, &GPIO_InitStructure);
|
||||
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN));
|
||||
adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount;
|
||||
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_601Cycles5;
|
||||
adcConfig[ADC_EXTERNAL1].enabled = true;
|
||||
|
@ -104,13 +157,20 @@ void adcInit(drv_adc_config_t *init)
|
|||
}
|
||||
#endif
|
||||
|
||||
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
|
||||
RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL | RCC_AHBPeriph_ADC12, ENABLE);
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
if (device == ADCINVALID)
|
||||
return;
|
||||
|
||||
adcDevice_t adc = adcHardware[device];
|
||||
|
||||
DMA_DeInit(ADC_DMA_CHANNEL);
|
||||
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
|
||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
||||
|
||||
DMA_DeInit(adc.DMAy_Channelx);
|
||||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->DR;
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
DMA_InitStructure.DMA_BufferSize = adcChannelCount;
|
||||
|
@ -122,20 +182,18 @@ void adcInit(drv_adc_config_t *init)
|
|||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
|
||||
DMA_Init(ADC_DMA_CHANNEL, &DMA_InitStructure);
|
||||
|
||||
DMA_Cmd(ADC_DMA_CHANNEL, ENABLE);
|
||||
DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure);
|
||||
|
||||
DMA_Cmd(adc.DMAy_Channelx, ENABLE);
|
||||
|
||||
// calibrate
|
||||
|
||||
ADC_VoltageRegulatorCmd(ADC_INSTANCE, ENABLE);
|
||||
ADC_VoltageRegulatorCmd(adc.ADCx, ENABLE);
|
||||
delay(10);
|
||||
ADC_SelectCalibrationMode(ADC_INSTANCE, ADC_CalibrationMode_Single);
|
||||
ADC_StartCalibration(ADC_INSTANCE);
|
||||
while(ADC_GetCalibrationStatus(ADC_INSTANCE) != RESET);
|
||||
ADC_VoltageRegulatorCmd(ADC_INSTANCE, DISABLE);
|
||||
|
||||
ADC_SelectCalibrationMode(adc.ADCx, ADC_CalibrationMode_Single);
|
||||
ADC_StartCalibration(adc.ADCx);
|
||||
while (ADC_GetCalibrationStatus(adc.ADCx) != RESET);
|
||||
ADC_VoltageRegulatorCmd(adc.ADCx, DISABLE);
|
||||
|
||||
ADC_CommonInitTypeDef ADC_CommonInitStructure;
|
||||
|
||||
|
@ -145,7 +203,7 @@ void adcInit(drv_adc_config_t *init)
|
|||
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1;
|
||||
ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular;
|
||||
ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0;
|
||||
ADC_CommonInit(ADC_INSTANCE, &ADC_CommonInitStructure);
|
||||
ADC_CommonInit(adc.ADCx, &ADC_CommonInitStructure);
|
||||
|
||||
ADC_StructInit(&ADC_InitStructure);
|
||||
|
||||
|
@ -158,24 +216,24 @@ void adcInit(drv_adc_config_t *init)
|
|||
ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable;
|
||||
ADC_InitStructure.ADC_NbrOfRegChannel = adcChannelCount;
|
||||
|
||||
ADC_Init(ADC_INSTANCE, &ADC_InitStructure);
|
||||
ADC_Init(adc.ADCx, &ADC_InitStructure);
|
||||
|
||||
uint8_t rank = 1;
|
||||
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||
if (!adcConfig[i].enabled) {
|
||||
continue;
|
||||
}
|
||||
ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
||||
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
||||
}
|
||||
|
||||
ADC_Cmd(ADC_INSTANCE, ENABLE);
|
||||
ADC_Cmd(adc.ADCx, ENABLE);
|
||||
|
||||
while(!ADC_GetFlagStatus(ADC_INSTANCE, ADC_FLAG_RDY));
|
||||
while (!ADC_GetFlagStatus(adc.ADCx, ADC_FLAG_RDY));
|
||||
|
||||
ADC_DMAConfig(ADC_INSTANCE, ADC_DMAMode_Circular);
|
||||
ADC_DMAConfig(adc.ADCx, ADC_DMAMode_Circular);
|
||||
|
||||
ADC_DMACmd(ADC_INSTANCE, ENABLE);
|
||||
ADC_DMACmd(adc.ADCx, ENABLE);
|
||||
|
||||
ADC_StartConversion(ADC_INSTANCE);
|
||||
ADC_StartConversion(adc.ADCx);
|
||||
}
|
||||
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#include "system.h"
|
||||
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#include "sensors/sensors.h" // FIXME dependency into the main code
|
||||
|
||||
|
@ -32,6 +34,56 @@
|
|||
#include "adc.h"
|
||||
#include "adc_impl.h"
|
||||
|
||||
#ifndef ADC_INSTANCE
|
||||
#define ADC_INSTANCE ADC1
|
||||
#endif
|
||||
|
||||
const adcDevice_t adcHardware[] = {
|
||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 },
|
||||
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
|
||||
};
|
||||
|
||||
/* note these could be packed up for saving space */
|
||||
const adcTagMap_t adcTagMap[] = {
|
||||
/*
|
||||
{ DEFIO_TAG_E__PF3, ADC_Channel_9 },
|
||||
{ DEFIO_TAG_E__PF4, ADC_Channel_14 },
|
||||
{ DEFIO_TAG_E__PF5, ADC_Channel_15 },
|
||||
{ DEFIO_TAG_E__PF6, ADC_Channel_4 },
|
||||
{ DEFIO_TAG_E__PF7, ADC_Channel_5 },
|
||||
{ DEFIO_TAG_E__PF8, ADC_Channel_6 },
|
||||
{ DEFIO_TAG_E__PF9, ADC_Channel_7 },
|
||||
{ DEFIO_TAG_E__PF10, ADC_Channel_8 },
|
||||
*/
|
||||
{ DEFIO_TAG_E__PC0, ADC_Channel_10 },
|
||||
{ DEFIO_TAG_E__PC1, ADC_Channel_11 },
|
||||
{ DEFIO_TAG_E__PC2, ADC_Channel_12 },
|
||||
{ DEFIO_TAG_E__PC3, ADC_Channel_13 },
|
||||
{ DEFIO_TAG_E__PC4, ADC_Channel_14 },
|
||||
{ DEFIO_TAG_E__PC5, ADC_Channel_15 },
|
||||
{ DEFIO_TAG_E__PB0, ADC_Channel_8 },
|
||||
{ DEFIO_TAG_E__PB1, ADC_Channel_9 },
|
||||
{ DEFIO_TAG_E__PA0, ADC_Channel_0 },
|
||||
{ DEFIO_TAG_E__PA1, ADC_Channel_1 },
|
||||
{ DEFIO_TAG_E__PA2, ADC_Channel_2 },
|
||||
{ DEFIO_TAG_E__PA3, ADC_Channel_3 },
|
||||
{ DEFIO_TAG_E__PA4, ADC_Channel_4 },
|
||||
{ DEFIO_TAG_E__PA5, ADC_Channel_5 },
|
||||
{ DEFIO_TAG_E__PA6, ADC_Channel_6 },
|
||||
{ DEFIO_TAG_E__PA7, ADC_Channel_7 },
|
||||
};
|
||||
|
||||
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||
{
|
||||
if (instance == ADC1)
|
||||
return ADCDEV_1;
|
||||
/*
|
||||
if (instance == ADC2) // TODO add ADC2 and 3
|
||||
return ADCDEV_2;
|
||||
*/
|
||||
return ADCINVALID;
|
||||
}
|
||||
|
||||
void adcInit(drv_adc_config_t *init)
|
||||
{
|
||||
ADC_InitTypeDef ADC_InitStructure;
|
||||
|
@ -50,7 +102,7 @@ void adcInit(drv_adc_config_t *init)
|
|||
if (init->enableVBat) {
|
||||
IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
|
||||
adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); //VBAT_ADC_CHANNEL;
|
||||
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_BATTERY].enabled = true;
|
||||
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles;
|
||||
|
@ -60,8 +112,8 @@ void adcInit(drv_adc_config_t *init)
|
|||
#ifdef EXTERNAL1_ADC_PIN
|
||||
if (init->enableExternal1) {
|
||||
IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); //EXTERNAL1_ADC_CHANNEL;
|
||||
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_EXTERNAL1].enabled = true;
|
||||
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles;
|
||||
|
@ -71,8 +123,8 @@ void adcInit(drv_adc_config_t *init)
|
|||
#ifdef RSSI_ADC_PIN
|
||||
if (init->enableRSSI) {
|
||||
IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); //RSSI_ADC_CHANNEL;
|
||||
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_RSSI].enabled = true;
|
||||
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles;
|
||||
|
@ -82,8 +134,8 @@ void adcInit(drv_adc_config_t *init)
|
|||
#ifdef CURRENT_METER_ADC_PIN
|
||||
if (init->enableCurrentMeter) {
|
||||
IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||
adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); //CURRENT_METER_ADC_CHANNEL;
|
||||
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_CURRENT].enabled = true;
|
||||
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles;
|
||||
|
@ -92,15 +144,20 @@ void adcInit(drv_adc_config_t *init)
|
|||
|
||||
//RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
|
||||
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE);
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
|
||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||
if (device == ADCINVALID)
|
||||
return;
|
||||
|
||||
adcDevice_t adc = adcHardware[device];
|
||||
|
||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||
|
||||
DMA_DeInit(DMA2_Stream4);
|
||||
DMA_DeInit(adc.DMAy_Streamx);
|
||||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
|
||||
DMA_InitStructure.DMA_Channel = DMA_Channel_0;
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR;
|
||||
DMA_InitStructure.DMA_Channel = adc.channel;
|
||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)adcValues;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||
DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
|
||||
|
@ -110,20 +167,9 @@ void adcInit(drv_adc_config_t *init)
|
|||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_Init(DMA2_Stream4, &DMA_InitStructure);
|
||||
DMA_Init(adc.DMAy_Streamx, &DMA_InitStructure);
|
||||
|
||||
DMA_Cmd(DMA2_Stream4, ENABLE);
|
||||
|
||||
// calibrate
|
||||
|
||||
/*
|
||||
ADC_VoltageRegulatorCmd(ADC1, ENABLE);
|
||||
delay(10);
|
||||
ADC_SelectCalibrationMode(ADC1, ADC_CalibrationMode_Single);
|
||||
ADC_StartCalibration(ADC1);
|
||||
while(ADC_GetCalibrationStatus(ADC1) != RESET);
|
||||
ADC_VoltageRegulatorCmd(ADC1, DISABLE);
|
||||
*/
|
||||
DMA_Cmd(adc.DMAy_Streamx, ENABLE);
|
||||
|
||||
ADC_CommonInitTypeDef ADC_CommonInitStructure;
|
||||
|
||||
|
@ -138,25 +184,25 @@ void adcInit(drv_adc_config_t *init)
|
|||
|
||||
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
|
||||
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
|
||||
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
|
||||
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
|
||||
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
|
||||
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
|
||||
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
|
||||
ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels;
|
||||
ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group
|
||||
ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group
|
||||
|
||||
ADC_Init(ADC1, &ADC_InitStructure);
|
||||
ADC_Init(adc.ADCx, &ADC_InitStructure);
|
||||
|
||||
uint8_t rank = 1;
|
||||
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||
if (!adcConfig[i].enabled) {
|
||||
continue;
|
||||
}
|
||||
ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
||||
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
||||
}
|
||||
ADC_DMARequestAfterLastTransferCmd(ADC1, ENABLE);
|
||||
ADC_DMARequestAfterLastTransferCmd(adc.ADCx, ENABLE);
|
||||
|
||||
ADC_DMACmd(ADC1, ENABLE);
|
||||
ADC_Cmd(ADC1, ENABLE);
|
||||
ADC_DMACmd(adc.ADCx, ENABLE);
|
||||
ADC_Cmd(adc.ADCx, ENABLE);
|
||||
|
||||
ADC_SoftwareStartConv(ADC1);
|
||||
ADC_SoftwareStartConv(adc.ADCx);
|
||||
}
|
||||
|
|
|
@ -45,8 +45,8 @@ static bool isEOCConnected = true;
|
|||
// EXTI14 for BMP085 End of Conversion Interrupt
|
||||
void bmp085_extiHandler(extiCallbackRec_t* cb)
|
||||
{
|
||||
UNUSED(cb);
|
||||
isConversionComplete = true;
|
||||
UNUSED(cb);
|
||||
isConversionComplete = true;
|
||||
}
|
||||
|
||||
bool bmp085TestEOCConnected(const bmp085Config_t *config);
|
||||
|
@ -184,13 +184,13 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
|
|||
|
||||
delay(20); // datasheet says 10ms, we'll be careful and do 20.
|
||||
|
||||
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
|
||||
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
|
||||
if (ack) {
|
||||
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
|
||||
bmp085.oversampling_setting = 3;
|
||||
|
||||
if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */
|
||||
bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */
|
||||
bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */
|
||||
bmp085_get_cal_param(); /* readout bmp085 calibparam structure */
|
||||
|
@ -277,7 +277,7 @@ static void bmp085_start_ut(void)
|
|||
#if defined(BARO_EOC_GPIO)
|
||||
isConversionComplete = false;
|
||||
#endif
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
|
||||
}
|
||||
|
||||
static void bmp085_get_ut(void)
|
||||
|
@ -291,7 +291,7 @@ static void bmp085_get_ut(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
|
||||
bmp085_ut = (data[0] << 8) | data[1];
|
||||
}
|
||||
|
||||
|
@ -305,7 +305,7 @@ static void bmp085_start_up(void)
|
|||
isConversionComplete = false;
|
||||
#endif
|
||||
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
|
||||
}
|
||||
|
||||
/** read out up for pressure conversion
|
||||
|
@ -323,7 +323,7 @@ static void bmp085_get_up(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
|
||||
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2])
|
||||
>> (8 - bmp085.oversampling_setting);
|
||||
}
|
||||
|
@ -343,7 +343,7 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature
|
|||
static void bmp085_get_cal_param(void)
|
||||
{
|
||||
uint8_t data[22];
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
|
||||
|
||||
/*parameters AC1-AC6*/
|
||||
bmp085.cal_param.ac1 = (data[0] << 8) | data[1];
|
||||
|
|
|
@ -18,8 +18,8 @@
|
|||
#pragma once
|
||||
|
||||
typedef struct bmp085Config_s {
|
||||
ioTag_t xclrIO;
|
||||
ioTag_t eocIO;
|
||||
ioTag_t xclrIO;
|
||||
ioTag_t eocIO;
|
||||
} bmp085Config_t;
|
||||
|
||||
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);
|
||||
|
|
|
@ -83,14 +83,14 @@ bool bmp280Detect(baro_t *baro)
|
|||
// set oversampling + power mode (forced), and start sampling
|
||||
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
#else
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
|
||||
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
|
||||
return false;
|
||||
|
||||
// read calibration
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
|
||||
// set oversampling + power mode (forced), and start sampling
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
#endif
|
||||
|
||||
bmp280InitDone = true;
|
||||
|
@ -129,7 +129,7 @@ static void bmp280_start_up(void)
|
|||
{
|
||||
// start measurement
|
||||
// set oversampling + power mode (forced), and start sampling
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
|
||||
}
|
||||
|
||||
static void bmp280_get_up(void)
|
||||
|
@ -137,7 +137,7 @@ static void bmp280_get_up(void)
|
|||
uint8_t data[BMP280_DATA_FRAME_SIZE];
|
||||
|
||||
// read data from sensor
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
|
||||
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
|
||||
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
|
||||
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
|
||||
}
|
||||
|
|
|
@ -67,7 +67,7 @@ bool ms5611Detect(baro_t *baro)
|
|||
|
||||
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
|
||||
|
||||
ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig);
|
||||
ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig);
|
||||
if (!ack)
|
||||
return false;
|
||||
|
||||
|
@ -93,14 +93,14 @@ bool ms5611Detect(baro_t *baro)
|
|||
|
||||
static void ms5611_reset(void)
|
||||
{
|
||||
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1);
|
||||
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1);
|
||||
delayMicroseconds(2800);
|
||||
}
|
||||
|
||||
static uint16_t ms5611_prom(int8_t coef_num)
|
||||
{
|
||||
uint8_t rxbuf[2] = { 0, 0 };
|
||||
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
|
||||
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
|
||||
return rxbuf[0] << 8 | rxbuf[1];
|
||||
}
|
||||
|
||||
|
@ -137,13 +137,13 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom)
|
|||
static uint32_t ms5611_read_adc(void)
|
||||
{
|
||||
uint8_t rxbuf[3];
|
||||
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
|
||||
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
|
||||
return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2];
|
||||
}
|
||||
|
||||
static void ms5611_start_ut(void)
|
||||
{
|
||||
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
|
||||
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
|
||||
}
|
||||
|
||||
static void ms5611_get_ut(void)
|
||||
|
@ -153,7 +153,7 @@ static void ms5611_get_ut(void)
|
|||
|
||||
static void ms5611_start_up(void)
|
||||
{
|
||||
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
|
||||
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
|
||||
}
|
||||
|
||||
static void ms5611_get_up(void)
|
||||
|
|
|
@ -28,12 +28,14 @@
|
|||
#include "barometer.h"
|
||||
#include "barometer_bmp280.h"
|
||||
|
||||
#define DISABLE_BMP280 GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN)
|
||||
#define ENABLE_BMP280 GPIO_ResetBits(BMP280_CS_GPIO, BMP280_CS_PIN)
|
||||
#define DISABLE_BMP280 IOHi(bmp280CsPin)
|
||||
#define ENABLE_BMP280 IOLo(bmp280CsPin)
|
||||
|
||||
extern int32_t bmp280_up;
|
||||
extern int32_t bmp280_ut;
|
||||
|
||||
static IO_t bmp280CsPin = IO_NONE;
|
||||
|
||||
bool bmp280WriteRegister(uint8_t reg, uint8_t data)
|
||||
{
|
||||
ENABLE_BMP280;
|
||||
|
@ -62,32 +64,13 @@ void bmp280SpiInit(void)
|
|||
return;
|
||||
}
|
||||
|
||||
#ifdef STM32F303
|
||||
RCC_AHBPeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN));
|
||||
IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI);
|
||||
IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = BMP280_CS_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
DISABLE_BMP280;
|
||||
|
||||
GPIO_Init(BMP280_CS_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
RCC_APB2PeriphClockCmd(BMP280_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
|
||||
gpio_config_t gpio;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpio.pin = BMP280_CS_PIN;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(BMP280_CS_GPIO, &gpio);
|
||||
#endif
|
||||
|
||||
GPIO_SetBits(BMP280_CS_GPIO, BMP280_CS_PIN);
|
||||
|
||||
spiSetDivisor(BMP280_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(BMP280_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
|
|
@ -48,218 +48,218 @@ static volatile uint16_t i2cErrorCount = 0;
|
|||
|
||||
static void I2C_delay(void)
|
||||
{
|
||||
volatile int i = 7;
|
||||
while (i) {
|
||||
i--;
|
||||
}
|
||||
volatile int i = 7;
|
||||
while (i) {
|
||||
i--;
|
||||
}
|
||||
}
|
||||
|
||||
static bool I2C_Start(void)
|
||||
{
|
||||
SDA_H;
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (!SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
return true;
|
||||
SDA_H;
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (!SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
return false;
|
||||
}
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
return true;
|
||||
}
|
||||
|
||||
static void I2C_Stop(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
}
|
||||
|
||||
static void I2C_Ack(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
}
|
||||
|
||||
static void I2C_NoAck(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
}
|
||||
|
||||
static bool I2C_WaitAck(void)
|
||||
{
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
SCL_L;
|
||||
return false;
|
||||
}
|
||||
SCL_L;
|
||||
return true;
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SDA_H;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
SCL_L;
|
||||
return false;
|
||||
}
|
||||
SCL_L;
|
||||
return true;
|
||||
}
|
||||
|
||||
static void I2C_SendByte(uint8_t byte)
|
||||
{
|
||||
uint8_t i = 8;
|
||||
while (i--) {
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
if (byte & 0x80) {
|
||||
SDA_H;
|
||||
}
|
||||
else {
|
||||
SDA_L;
|
||||
}
|
||||
byte <<= 1;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
}
|
||||
SCL_L;
|
||||
uint8_t i = 8;
|
||||
while (i--) {
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
if (byte & 0x80) {
|
||||
SDA_H;
|
||||
}
|
||||
else {
|
||||
SDA_L;
|
||||
}
|
||||
byte <<= 1;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
}
|
||||
SCL_L;
|
||||
}
|
||||
|
||||
static uint8_t I2C_ReceiveByte(void)
|
||||
{
|
||||
uint8_t i = 8;
|
||||
uint8_t byte = 0;
|
||||
uint8_t i = 8;
|
||||
uint8_t byte = 0;
|
||||
|
||||
SDA_H;
|
||||
while (i--) {
|
||||
byte <<= 1;
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
byte |= 0x01;
|
||||
}
|
||||
}
|
||||
SCL_L;
|
||||
return byte;
|
||||
SDA_H;
|
||||
while (i--) {
|
||||
byte <<= 1;
|
||||
SCL_L;
|
||||
I2C_delay();
|
||||
SCL_H;
|
||||
I2C_delay();
|
||||
if (SDA_read) {
|
||||
byte |= 0x01;
|
||||
}
|
||||
}
|
||||
SCL_L;
|
||||
return byte;
|
||||
}
|
||||
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
UNUSED(device);
|
||||
UNUSED(device);
|
||||
|
||||
scl = IOGetByTag(IO_TAG(SOFT_I2C_SCL));
|
||||
sda = IOGetByTag(IO_TAG(SOFT_I2C_SDA));
|
||||
scl = IOGetByTag(IO_TAG(SOFT_I2C_SCL));
|
||||
sda = IOGetByTag(IO_TAG(SOFT_I2C_SDA));
|
||||
|
||||
IOConfigGPIO(scl, IOCFG_OUT_OD);
|
||||
IOConfigGPIO(sda, IOCFG_OUT_OD);
|
||||
IOConfigGPIO(scl, IOCFG_OUT_OD);
|
||||
IOConfigGPIO(sda, IOCFG_OUT_OD);
|
||||
}
|
||||
|
||||
bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
|
||||
{
|
||||
UNUSED(device);
|
||||
|
||||
int i;
|
||||
if (!I2C_Start()) {
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
for (i = 0; i < len; i++) {
|
||||
I2C_SendByte(data[i]);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
int i;
|
||||
if (!I2C_Start()) {
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
for (i = 0; i < len; i++) {
|
||||
I2C_SendByte(data[i]);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data)
|
||||
{
|
||||
UNUSED(device);
|
||||
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_SendByte(data);
|
||||
I2C_WaitAck();
|
||||
I2C_Stop();
|
||||
return true;
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_SendByte(data);
|
||||
I2C_WaitAck();
|
||||
I2C_Stop();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
|
||||
{
|
||||
UNUSED(device);
|
||||
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_Start();
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
|
||||
I2C_WaitAck();
|
||||
while (len) {
|
||||
*buf = I2C_ReceiveByte();
|
||||
if (len == 1) {
|
||||
I2C_NoAck();
|
||||
}
|
||||
else {
|
||||
I2C_Ack();
|
||||
}
|
||||
buf++;
|
||||
len--;
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
if (!I2C_Start()) {
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
|
||||
if (!I2C_WaitAck()) {
|
||||
I2C_Stop();
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
I2C_SendByte(reg);
|
||||
I2C_WaitAck();
|
||||
I2C_Start();
|
||||
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
|
||||
I2C_WaitAck();
|
||||
while (len) {
|
||||
*buf = I2C_ReceiveByte();
|
||||
if (len == 1) {
|
||||
I2C_NoAck();
|
||||
}
|
||||
else {
|
||||
I2C_Ack();
|
||||
}
|
||||
buf++;
|
||||
len--;
|
||||
}
|
||||
I2C_Stop();
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t i2cGetErrorCounter(void)
|
||||
{
|
||||
return i2cErrorCount;
|
||||
return i2cErrorCount;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -82,10 +82,10 @@ static void i2cUnstick(IO_t scl, IO_t sda);
|
|||
#endif
|
||||
|
||||
static i2cDevice_t i2cHardwareMap[] = {
|
||||
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn },
|
||||
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn },
|
||||
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn },
|
||||
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn },
|
||||
#ifdef STM32F4
|
||||
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = false, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn }
|
||||
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = I2C2_OVERCLOCK, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn }
|
||||
#endif
|
||||
};
|
||||
|
||||
|
@ -396,7 +396,7 @@ void i2cInit(I2CDevice device)
|
|||
i2cUnstick(scl, sda);
|
||||
|
||||
// Init pins
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
|
||||
#ifdef STM32F4
|
||||
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
|
||||
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
|
||||
#else
|
||||
|
@ -416,8 +416,7 @@ void i2cInit(I2CDevice device)
|
|||
|
||||
if (i2c->overClock) {
|
||||
i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs
|
||||
}
|
||||
|
||||
|
|
|
@ -54,8 +54,8 @@ static volatile uint16_t i2cErrorCount = 0;
|
|||
//static volatile uint16_t i2c2ErrorCount = 0;
|
||||
|
||||
static i2cDevice_t i2cHardwareMap[] = {
|
||||
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false },
|
||||
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false }
|
||||
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = I2C1_OVERCLOCK },
|
||||
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = I2C2_OVERCLOCK }
|
||||
};
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -64,190 +64,189 @@ static i2cDevice_t i2cHardwareMap[] = {
|
|||
|
||||
uint32_t i2cTimeoutUserCallback(void)
|
||||
{
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
i2cErrorCount++;
|
||||
return false;
|
||||
}
|
||||
|
||||
void i2cInit(I2CDevice device)
|
||||
{
|
||||
|
||||
i2cDevice_t *i2c;
|
||||
i2c = &(i2cHardwareMap[device]);
|
||||
i2cDevice_t *i2c;
|
||||
i2c = &(i2cHardwareMap[device]);
|
||||
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2c->dev;
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2c->dev;
|
||||
|
||||
IO_t scl = IOGetByTag(i2c->scl);
|
||||
IO_t sda = IOGetByTag(i2c->sda);
|
||||
IO_t scl = IOGetByTag(i2c->scl);
|
||||
IO_t sda = IOGetByTag(i2c->sda);
|
||||
|
||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||
|
||||
IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
|
||||
IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
|
||||
IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
|
||||
IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
|
||||
|
||||
I2C_InitTypeDef i2cInit = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
|
||||
.I2C_DigitalFilter = 0x00,
|
||||
.I2C_OwnAddress1 = 0x00,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_Timing = 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
//.I2C_Timing = 0x8000050B;
|
||||
};
|
||||
I2C_InitTypeDef i2cInit = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
|
||||
.I2C_DigitalFilter = 0x00,
|
||||
.I2C_OwnAddress1 = 0x00,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_Timing = i2c->overClock ?
|
||||
0x00500E30 : // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
||||
0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
//.I2C_Timing = 0x8000050B;
|
||||
};
|
||||
|
||||
if (i2c->overClock) {
|
||||
i2cInit.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
||||
}
|
||||
I2C_Init(I2Cx, &i2cInit);
|
||||
I2C_Init(I2Cx, &i2cInit);
|
||||
|
||||
I2C_Cmd(I2Cx, ENABLE);
|
||||
I2C_Cmd(I2Cx, ENABLE);
|
||||
}
|
||||
|
||||
uint16_t i2cGetErrorCounter(void)
|
||||
{
|
||||
return i2cErrorCount;
|
||||
return i2cErrorCount;
|
||||
}
|
||||
|
||||
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
|
||||
{
|
||||
addr_ <<= 1;
|
||||
addr_ <<= 1;
|
||||
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2cHardwareMap[device].dev;
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2cHardwareMap[device].dev;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TCR flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
|
||||
{
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until TCR flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
|
||||
{
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Write data to TXDR */
|
||||
I2C_SendData(I2Cx, data);
|
||||
/* Write data to TXDR */
|
||||
I2C_SendData(I2Cx, data);
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
return true;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
addr_ <<= 1;
|
||||
addr_ <<= 1;
|
||||
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2cHardwareMap[device].dev;
|
||||
I2C_TypeDef *I2Cx;
|
||||
I2Cx = i2cHardwareMap[device].dev;
|
||||
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Test on BUSY Flag */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
|
||||
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until TXIS flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
/* Send Register address */
|
||||
I2C_SendData(I2Cx, (uint8_t) reg);
|
||||
|
||||
/* Wait until TC flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until TC flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
|
||||
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
|
||||
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
|
||||
|
||||
/* Wait until all data are received */
|
||||
while (len) {
|
||||
/* Wait until RXNE flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until all data are received */
|
||||
while (len) {
|
||||
/* Wait until RXNE flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Read data from RXDR */
|
||||
*buf = I2C_ReceiveData(I2Cx);
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
buf++;
|
||||
/* Read data from RXDR */
|
||||
*buf = I2C_ReceiveData(I2Cx);
|
||||
/* Point to the next location where the byte read will be saved */
|
||||
buf++;
|
||||
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
/* Decrement the read bytes counter */
|
||||
len--;
|
||||
}
|
||||
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
/* Wait until STOPF flag is set */
|
||||
i2cTimeout = I2C_LONG_TIMEOUT;
|
||||
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
|
||||
if ((i2cTimeout--) == 0) {
|
||||
return i2cTimeoutUserCallback();
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
/* Clear STOPF flag */
|
||||
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
|
||||
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
/* If all operations OK */
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
#define GPIO_AF_SPI2 GPIO_AF_5
|
||||
#endif
|
||||
#ifndef GPIO_AF_SPI3
|
||||
#define GPIO_AF_SPI3 GPIO_AF_6
|
||||
#define GPIO_AF_SPI3 GPIO_AF_6
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
@ -72,169 +72,169 @@
|
|||
#endif
|
||||
|
||||
static spiDevice_t spiHardwareMap[] = {
|
||||
#if defined(STM32F10X)
|
||||
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false },
|
||||
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false },
|
||||
#if defined(STM32F1)
|
||||
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false },
|
||||
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false },
|
||||
#else
|
||||
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false },
|
||||
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false },
|
||||
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false },
|
||||
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false },
|
||||
#endif
|
||||
#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE)
|
||||
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false }
|
||||
#if defined(STM32F3) || defined(STM32F4)
|
||||
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false }
|
||||
#endif
|
||||
};
|
||||
|
||||
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||
{
|
||||
if (instance == SPI1)
|
||||
return SPIDEV_1;
|
||||
if (instance == SPI1)
|
||||
return SPIDEV_1;
|
||||
|
||||
if (instance == SPI2)
|
||||
return SPIDEV_2;
|
||||
if (instance == SPI2)
|
||||
return SPIDEV_2;
|
||||
|
||||
if (instance == SPI3)
|
||||
return SPIDEV_3;
|
||||
if (instance == SPI3)
|
||||
return SPIDEV_3;
|
||||
|
||||
return SPIINVALID;
|
||||
return SPIINVALID;
|
||||
}
|
||||
|
||||
void spiInitDevice(SPIDevice device)
|
||||
{
|
||||
SPI_InitTypeDef spiInit;
|
||||
SPI_InitTypeDef spiInit;
|
||||
|
||||
spiDevice_t *spi = &(spiHardwareMap[device]);
|
||||
spiDevice_t *spi = &(spiHardwareMap[device]);
|
||||
|
||||
#ifdef SDCARD_SPI_INSTANCE
|
||||
if (spi->dev == SDCARD_SPI_INSTANCE)
|
||||
spi->sdcard = true;
|
||||
if (spi->dev == SDCARD_SPI_INSTANCE)
|
||||
spi->sdcard = true;
|
||||
#endif
|
||||
|
||||
// Enable SPI clock
|
||||
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||
// Enable SPI clock
|
||||
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||
|
||||
IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI);
|
||||
|
||||
#if defined(STM32F303xC) || defined(STM32F4)
|
||||
if (spi->sdcard) {
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af);
|
||||
}
|
||||
else {
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
|
||||
}
|
||||
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
|
||||
if (spi->sdcard) {
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af);
|
||||
}
|
||||
else {
|
||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
|
||||
}
|
||||
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
|
||||
|
||||
if (spi->nss)
|
||||
IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af);
|
||||
if (spi->nss)
|
||||
IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af);
|
||||
#endif
|
||||
#if defined(STM32F10X)
|
||||
IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_CFG);
|
||||
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_CFG);
|
||||
|
||||
if (spi->nss)
|
||||
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
|
||||
if (spi->nss)
|
||||
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
|
||||
#endif
|
||||
|
||||
// Init SPI hardware
|
||||
SPI_I2S_DeInit(spi->dev);
|
||||
// Init SPI hardware
|
||||
SPI_I2S_DeInit(spi->dev);
|
||||
|
||||
spiInit.SPI_Mode = SPI_Mode_Master;
|
||||
spiInit.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
|
||||
spiInit.SPI_DataSize = SPI_DataSize_8b;
|
||||
spiInit.SPI_NSS = SPI_NSS_Soft;
|
||||
spiInit.SPI_FirstBit = SPI_FirstBit_MSB;
|
||||
spiInit.SPI_CRCPolynomial = 7;
|
||||
spiInit.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
spiInit.SPI_Mode = SPI_Mode_Master;
|
||||
spiInit.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
|
||||
spiInit.SPI_DataSize = SPI_DataSize_8b;
|
||||
spiInit.SPI_NSS = SPI_NSS_Soft;
|
||||
spiInit.SPI_FirstBit = SPI_FirstBit_MSB;
|
||||
spiInit.SPI_CRCPolynomial = 7;
|
||||
spiInit.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
|
||||
if (spi->sdcard) {
|
||||
spiInit.SPI_CPOL = SPI_CPOL_Low;
|
||||
spiInit.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
}
|
||||
else {
|
||||
spiInit.SPI_CPOL = SPI_CPOL_High;
|
||||
spiInit.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
}
|
||||
if (spi->sdcard) {
|
||||
spiInit.SPI_CPOL = SPI_CPOL_Low;
|
||||
spiInit.SPI_CPHA = SPI_CPHA_1Edge;
|
||||
}
|
||||
else {
|
||||
spiInit.SPI_CPOL = SPI_CPOL_High;
|
||||
spiInit.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
// Configure for 8-bit reads.
|
||||
SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF);
|
||||
// Configure for 8-bit reads.
|
||||
SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF);
|
||||
#endif
|
||||
|
||||
SPI_Init(spi->dev, &spiInit);
|
||||
SPI_Cmd(spi->dev, ENABLE);
|
||||
SPI_Init(spi->dev, &spiInit);
|
||||
SPI_Cmd(spi->dev, ENABLE);
|
||||
|
||||
if (spi->nss)
|
||||
IOHi(IOGetByTag(spi->nss));
|
||||
if (spi->nss)
|
||||
IOHi(IOGetByTag(spi->nss));
|
||||
}
|
||||
|
||||
bool spiInit(SPIDevice device)
|
||||
{
|
||||
switch (device)
|
||||
{
|
||||
case SPIINVALID:
|
||||
return false;
|
||||
case SPIDEV_1:
|
||||
switch (device)
|
||||
{
|
||||
case SPIINVALID:
|
||||
return false;
|
||||
case SPIDEV_1:
|
||||
#ifdef USE_SPI_DEVICE_1
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
#else
|
||||
break;
|
||||
break;
|
||||
#endif
|
||||
case SPIDEV_2:
|
||||
case SPIDEV_2:
|
||||
#ifdef USE_SPI_DEVICE_2
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
#else
|
||||
break;
|
||||
break;
|
||||
#endif
|
||||
case SPIDEV_3:
|
||||
case SPIDEV_3:
|
||||
#if defined(USE_SPI_DEVICE_3) && (defined(STM32F303xC) || defined(STM32F4))
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
spiInitDevice(device);
|
||||
return true;
|
||||
#else
|
||||
break;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if (device == SPIINVALID)
|
||||
return -1;
|
||||
spiHardwareMap[device].errorCount++;
|
||||
return spiHardwareMap[device].errorCount;
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if (device == SPIINVALID)
|
||||
return -1;
|
||||
spiHardwareMap[device].errorCount++;
|
||||
return spiHardwareMap[device].errorCount;
|
||||
}
|
||||
|
||||
// return uint8_t value or -1 when failure
|
||||
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
|
||||
{
|
||||
uint16_t spiTimeout = 1000;
|
||||
uint16_t spiTimeout = 1000;
|
||||
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET)
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET)
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
|
||||
#ifdef STM32F303xC
|
||||
SPI_SendData8(instance, data);
|
||||
SPI_SendData8(instance, data);
|
||||
#else
|
||||
SPI_I2S_SendData(instance, data);
|
||||
SPI_I2S_SendData(instance, data);
|
||||
#endif
|
||||
spiTimeout = 1000;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET)
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
spiTimeout = 1000;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET)
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
|
||||
#ifdef STM32F303xC
|
||||
return ((uint8_t)SPI_ReceiveData8(instance));
|
||||
return ((uint8_t)SPI_ReceiveData8(instance));
|
||||
#else
|
||||
return ((uint8_t)SPI_I2S_ReceiveData(instance));
|
||||
return ((uint8_t)SPI_I2S_ReceiveData(instance));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -244,118 +244,115 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
|
|||
bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||
{
|
||||
#ifdef STM32F303xC
|
||||
return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
|
||||
return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
|
||||
#else
|
||||
return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
|
||||
return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
|
||||
{
|
||||
uint16_t spiTimeout = 1000;
|
||||
uint16_t spiTimeout = 1000;
|
||||
|
||||
uint8_t b;
|
||||
instance->DR;
|
||||
while (len--) {
|
||||
b = in ? *(in++) : 0xFF;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
uint8_t b;
|
||||
instance->DR;
|
||||
while (len--) {
|
||||
b = in ? *(in++) : 0xFF;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
#ifdef STM32F303xC
|
||||
SPI_SendData8(instance, b);
|
||||
//SPI_I2S_SendData16(instance, b);
|
||||
SPI_SendData8(instance, b);
|
||||
#else
|
||||
SPI_I2S_SendData(instance, b);
|
||||
SPI_I2S_SendData(instance, b);
|
||||
#endif
|
||||
spiTimeout = 1000;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
spiTimeout = 1000;
|
||||
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
if ((spiTimeout--) == 0)
|
||||
return spiTimeoutUserCallback(instance);
|
||||
}
|
||||
#ifdef STM32F303xC
|
||||
b = SPI_ReceiveData8(instance);
|
||||
//b = SPI_I2S_ReceiveData16(instance);
|
||||
b = SPI_ReceiveData8(instance);
|
||||
#else
|
||||
b = SPI_I2S_ReceiveData(instance);
|
||||
b = SPI_I2S_ReceiveData(instance);
|
||||
#endif
|
||||
if (out)
|
||||
*(out++) = b;
|
||||
}
|
||||
if (out)
|
||||
*(out++) = b;
|
||||
}
|
||||
|
||||
return true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||
{
|
||||
#define BR_CLEAR_MASK 0xFFC7
|
||||
|
||||
uint16_t tempRegister;
|
||||
uint16_t tempRegister;
|
||||
|
||||
SPI_Cmd(instance, DISABLE);
|
||||
SPI_Cmd(instance, DISABLE);
|
||||
|
||||
tempRegister = instance->CR1;
|
||||
tempRegister = instance->CR1;
|
||||
|
||||
switch (divisor) {
|
||||
case 2:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_2;
|
||||
break;
|
||||
switch (divisor) {
|
||||
case 2:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_2;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_4;
|
||||
break;
|
||||
case 4:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_4;
|
||||
break;
|
||||
|
||||
case 8:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_8;
|
||||
break;
|
||||
case 8:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_8;
|
||||
break;
|
||||
|
||||
case 16:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_16;
|
||||
break;
|
||||
case 16:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_16;
|
||||
break;
|
||||
|
||||
case 32:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_32;
|
||||
break;
|
||||
case 32:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_32;
|
||||
break;
|
||||
|
||||
case 64:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_64;
|
||||
break;
|
||||
case 64:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_64;
|
||||
break;
|
||||
|
||||
case 128:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_128;
|
||||
break;
|
||||
case 128:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_128;
|
||||
break;
|
||||
|
||||
case 256:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_256;
|
||||
break;
|
||||
}
|
||||
case 256:
|
||||
tempRegister &= BR_CLEAR_MASK;
|
||||
tempRegister |= SPI_BaudRatePrescaler_256;
|
||||
break;
|
||||
}
|
||||
|
||||
instance->CR1 = tempRegister;
|
||||
instance->CR1 = tempRegister;
|
||||
|
||||
SPI_Cmd(instance, ENABLE);
|
||||
SPI_Cmd(instance, ENABLE);
|
||||
}
|
||||
|
||||
uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if (device == SPIINVALID)
|
||||
return 0;
|
||||
return spiHardwareMap[device].errorCount;
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if (device == SPIINVALID)
|
||||
return 0;
|
||||
return spiHardwareMap[device].errorCount;
|
||||
}
|
||||
|
||||
void spiResetErrorCounter(SPI_TypeDef *instance)
|
||||
{
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if (device != SPIINVALID)
|
||||
spiHardwareMap[device].errorCount = 0;
|
||||
SPIDevice device = spiDeviceByInstance(instance);
|
||||
if (device != SPIINVALID)
|
||||
spiHardwareMap[device].errorCount = 0;
|
||||
}
|
|
@ -17,60 +17,58 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define SPI_0_28125MHZ_CLOCK_DIVIDER 256
|
||||
#define SPI_0_5625MHZ_CLOCK_DIVIDER 128
|
||||
#define SPI_18MHZ_CLOCK_DIVIDER 2
|
||||
#define SPI_9MHZ_CLOCK_DIVIDER 4
|
||||
|
||||
#include <stdint.h>
|
||||
#include "io.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined (STM32F411xE) || defined(STM32F303xC)
|
||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
|
||||
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||
#elif defined(STM32F10X)
|
||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz)
|
||||
#if defined(STM32F4) || defined(STM32F3)
|
||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
|
||||
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
|
||||
#elif defined(STM32F1)
|
||||
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
|
||||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz)
|
||||
#else
|
||||
#error "Unknown processor"
|
||||
#endif
|
||||
#if defined(STM32F40_41xxx) || defined (STM32F411xE)
|
||||
|
||||
#define SPI_SLOW_CLOCK 128 //00.65625 MHz
|
||||
#define SPI_STANDARD_CLOCK 8 //11.50000 MHz
|
||||
#define SPI_FAST_CLOCK 4 //21.00000 MHz
|
||||
#define SPI_ULTRAFAST_CLOCK 2 //42.00000 MHz
|
||||
|
||||
/*
|
||||
Flash M25p16 tolerates 20mhz, SPI_CLOCK_FAST should sit around 20 or less.
|
||||
*/
|
||||
typedef enum {
|
||||
SPI_CLOCK_INITIALIZATON = 256,
|
||||
#if defined(STM32F4)
|
||||
SPI_CLOCK_SLOW = 128, //00.65625 MHz
|
||||
SPI_CLOCK_STANDARD = 8, //10.50000 MHz
|
||||
SPI_CLOCK_FAST = 4, //21.00000 MHz
|
||||
SPI_CLOCK_ULTRAFAST = 2, //42.00000 MHz
|
||||
#else
|
||||
|
||||
#define SPI_SLOW_CLOCK 128 //00.56250 MHz
|
||||
#define SPI_STANDARD_CLOCK 4 //09.00000 MHz
|
||||
#define SPI_FAST_CLOCK 2 //18.00000 MHz
|
||||
#define SPI_ULTRAFAST_CLOCK 2 //18.00000 MHz
|
||||
|
||||
SPI_CLOCK_SLOW = 128, //00.56250 MHz
|
||||
SPI_CLOCK_STANDARD = 4, //09.00000 MHz
|
||||
SPI_CLOCK_FAST = 2, //18.00000 MHz
|
||||
SPI_CLOCK_ULTRAFAST = 2, //18.00000 MHz
|
||||
#endif
|
||||
} SPIClockDivider_e;
|
||||
|
||||
typedef enum SPIDevice {
|
||||
SPIINVALID = -1,
|
||||
SPIDEV_1 = 0,
|
||||
SPIDEV_2,
|
||||
SPIDEV_3,
|
||||
SPIDEV_MAX = SPIDEV_3,
|
||||
SPIINVALID = -1,
|
||||
SPIDEV_1 = 0,
|
||||
SPIDEV_2,
|
||||
SPIDEV_3,
|
||||
SPIDEV_MAX = SPIDEV_3,
|
||||
} SPIDevice;
|
||||
|
||||
typedef struct SPIDevice_s {
|
||||
SPI_TypeDef *dev;
|
||||
ioTag_t nss;
|
||||
ioTag_t sck;
|
||||
ioTag_t mosi;
|
||||
ioTag_t miso;
|
||||
rccPeriphTag_t rcc;
|
||||
uint8_t af;
|
||||
volatile uint16_t errorCount;
|
||||
bool sdcard;
|
||||
SPI_TypeDef *dev;
|
||||
ioTag_t nss;
|
||||
ioTag_t sck;
|
||||
ioTag_t mosi;
|
||||
ioTag_t miso;
|
||||
rccPeriphTag_t rcc;
|
||||
uint8_t af;
|
||||
volatile uint16_t errorCount;
|
||||
bool sdcard;
|
||||
} spiDevice_t;
|
||||
|
||||
bool spiInit(SPIDevice device);
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
#include "gpio.h"
|
||||
#include "exti.h"
|
||||
#include "bus_i2c.h"
|
||||
#include "bus_spi.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -42,7 +43,9 @@
|
|||
|
||||
#include "accgyro.h"
|
||||
#include "accgyro_mpu.h"
|
||||
#include "accgyro_mpu6500.h"
|
||||
#include "accgyro_spi_mpu6500.h"
|
||||
#include "accgyro_spi_mpu9250.h"
|
||||
#include "compass_ak8963.h"
|
||||
|
||||
// This sensor is available in MPU-9250.
|
||||
|
@ -83,18 +86,10 @@
|
|||
#define CNTL_MODE_SELF_TEST 0x08
|
||||
#define CNTL_MODE_FUSE_ROM 0x0F
|
||||
|
||||
typedef bool (*ak8963ReadRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf);
|
||||
typedef bool (*ak8963WriteRegisterFunc)(uint8_t addr_, uint8_t reg_, uint8_t data);
|
||||
|
||||
typedef struct ak8963Configuration_s {
|
||||
ak8963ReadRegisterFunc read;
|
||||
ak8963WriteRegisterFunc write;
|
||||
} ak8963Configuration_t;
|
||||
|
||||
ak8963Configuration_t ak8963config;
|
||||
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||
|
||||
// FIXME pretend we have real MPU9250 support
|
||||
// Is an separate MPU9250 driver really needed? The GYRO/ACC part between MPU6500 and MPU9250 is exactly the same.
|
||||
#if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE)
|
||||
#define MPU9250_SPI_INSTANCE
|
||||
#define verifympu9250WriteRegister mpu6500WriteRegister
|
||||
|
@ -102,30 +97,7 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
|||
#define mpu9250ReadRegister mpu6500ReadRegister
|
||||
#endif
|
||||
|
||||
#ifdef USE_SPI
|
||||
bool ak8963SPIRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
||||
{
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||
delay(8);
|
||||
__disable_irq();
|
||||
mpu6500ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
|
||||
__enable_irq();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool ak8963SPIWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||
{
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
|
||||
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef SPRACINGF3EVO
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
|
||||
typedef struct queuedReadState_s {
|
||||
bool waiting;
|
||||
|
@ -133,9 +105,36 @@ typedef struct queuedReadState_s {
|
|||
uint32_t readStartedAt; // time read was queued in micros.
|
||||
} queuedReadState_t;
|
||||
|
||||
typedef enum {
|
||||
CHECK_STATUS = 0,
|
||||
WAITING_FOR_STATUS,
|
||||
WAITING_FOR_DATA
|
||||
} ak8963ReadState_e;
|
||||
|
||||
static queuedReadState_t queuedRead = { false, 0, 0};
|
||||
|
||||
bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
|
||||
bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
||||
{
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||
delay(10);
|
||||
__disable_irq();
|
||||
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
|
||||
__enable_irq();
|
||||
return true;
|
||||
}
|
||||
|
||||
bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||
{
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
|
||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
|
||||
return true;
|
||||
}
|
||||
|
||||
bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
|
||||
{
|
||||
if (queuedRead.waiting) {
|
||||
return false;
|
||||
|
@ -153,7 +152,7 @@ bool ak8963SPIStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
|
|||
return true;
|
||||
}
|
||||
|
||||
static uint32_t ak8963SPIQueuedReadTimeRemaining(void)
|
||||
static uint32_t ak8963SensorQueuedReadTimeRemaining(void)
|
||||
{
|
||||
if (!queuedRead.waiting) {
|
||||
return 0;
|
||||
|
@ -170,9 +169,9 @@ static uint32_t ak8963SPIQueuedReadTimeRemaining(void)
|
|||
return timeRemaining;
|
||||
}
|
||||
|
||||
bool ak8963SPICompleteRead(uint8_t *buf)
|
||||
bool ak8963SensorCompleteRead(uint8_t *buf)
|
||||
{
|
||||
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
|
||||
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
|
||||
|
||||
if (timeRemaining > 0) {
|
||||
delayMicroseconds(timeRemaining);
|
||||
|
@ -183,18 +182,15 @@ bool ak8963SPICompleteRead(uint8_t *buf)
|
|||
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C
|
||||
bool c_i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||
#else
|
||||
bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data);
|
||||
return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf);
|
||||
}
|
||||
|
||||
bool c_i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
|
||||
bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||
{
|
||||
return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf);
|
||||
return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -203,43 +199,28 @@ bool ak8963Detect(mag_t *mag)
|
|||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
#ifdef USE_I2C
|
||||
// check for AK8963 on I2C bus
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
// initialze I2C master via SPI bus (MPU9250)
|
||||
|
||||
ack = verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
|
||||
delay(10);
|
||||
|
||||
ack = verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||
delay(10);
|
||||
|
||||
ack = verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||
delay(10);
|
||||
#endif
|
||||
|
||||
// check for AK8963
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
|
||||
{
|
||||
ak8963config.read = c_i2cRead;
|
||||
ak8963config.write = c_i2cWrite;
|
||||
mag->init = ak8963Init;
|
||||
mag->read = ak8963Read;
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SPI
|
||||
// check for AK8963 on I2C master via SPI bus (as part of MPU9250)
|
||||
|
||||
ack = mpu6500WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
|
||||
delay(10);
|
||||
|
||||
ack = mpu6500WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||
delay(10);
|
||||
|
||||
ack = mpu6500WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||
delay(10);
|
||||
|
||||
ack = ak8963SPIRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
|
||||
{
|
||||
ak8963config.read = ak8963SPIRead;
|
||||
ak8963config.write = ak8963SPIWrite;
|
||||
mag->init = ak8963Init;
|
||||
mag->read = ak8963Read;
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -250,49 +231,43 @@ void ak8963Init()
|
|||
uint8_t calibration[3];
|
||||
uint8_t status;
|
||||
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
|
||||
delay(20);
|
||||
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
||||
delay(10);
|
||||
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
|
||||
delay(10);
|
||||
|
||||
magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30);
|
||||
magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30);
|
||||
magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30);
|
||||
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
|
||||
delay(10);
|
||||
|
||||
// Clear status registers
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||
|
||||
// Trigger first measurement
|
||||
#ifdef SPRACINGF3EVO
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
||||
#else
|
||||
ack = ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||
#endif
|
||||
}
|
||||
|
||||
typedef enum {
|
||||
CHECK_STATUS = 0,
|
||||
WAITING_FOR_STATUS,
|
||||
WAITING_FOR_DATA
|
||||
} ak8963ReadState_e;
|
||||
|
||||
bool ak8963Read(int16_t *magData)
|
||||
{
|
||||
bool ack;
|
||||
bool ack = false;
|
||||
uint8_t buf[7];
|
||||
|
||||
#ifdef SPRACINGF3EVO
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
|
||||
// we currently need a different approach on the SPRacingF3EVO which has an MPU9250 connected via SPI.
|
||||
// we cannot use the ak8963SPIRead() method, it is to slow and blocks for far too long.
|
||||
// we currently need a different approach for the MPU9250 connected via SPI.
|
||||
// we cannot use the ak8963SensorRead() method for SPI, it is to slow and blocks for far too long.
|
||||
|
||||
static ak8963ReadState_e state = CHECK_STATUS;
|
||||
|
||||
|
@ -301,17 +276,17 @@ bool ak8963Read(int16_t *magData)
|
|||
restart:
|
||||
switch (state) {
|
||||
case CHECK_STATUS:
|
||||
ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1);
|
||||
ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1);
|
||||
state++;
|
||||
return false;
|
||||
|
||||
case WAITING_FOR_STATUS: {
|
||||
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
|
||||
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
|
||||
if (timeRemaining) {
|
||||
return false;
|
||||
}
|
||||
|
||||
ack = ak8963SPICompleteRead(&buf[0]);
|
||||
ack = ak8963SensorCompleteRead(&buf[0]);
|
||||
|
||||
uint8_t status = buf[0];
|
||||
|
||||
|
@ -327,7 +302,7 @@ restart:
|
|||
|
||||
|
||||
// read the 6 bytes of data and the status2 register
|
||||
ak8963SPIStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7);
|
||||
ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7);
|
||||
|
||||
state++;
|
||||
|
||||
|
@ -335,31 +310,16 @@ restart:
|
|||
}
|
||||
|
||||
case WAITING_FOR_DATA: {
|
||||
uint32_t timeRemaining = ak8963SPIQueuedReadTimeRemaining();
|
||||
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
|
||||
if (timeRemaining) {
|
||||
return false;
|
||||
}
|
||||
|
||||
ack = ak8963SPICompleteRead(&buf[0]);
|
||||
|
||||
uint8_t status2 = buf[6];
|
||||
if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
magData[X] = -(int16_t)(buf[1] << 8 | buf[0]) * magGain[X];
|
||||
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
||||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
||||
|
||||
state = CHECK_STATUS;
|
||||
|
||||
return true;
|
||||
ack = ak8963SensorCompleteRead(&buf[0]);
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
#else
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]);
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]);
|
||||
|
||||
uint8_t status = buf[0];
|
||||
|
||||
|
@ -367,8 +327,8 @@ restart:
|
|||
return false;
|
||||
}
|
||||
|
||||
ack = ak8963config.read(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]);
|
||||
|
||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7, &buf[0]);
|
||||
#endif
|
||||
uint8_t status2 = buf[6];
|
||||
if (!ack || (status2 & STATUS2_DATA_ERROR) || (status2 & STATUS2_MAG_SENSOR_OVERFLOW)) {
|
||||
return false;
|
||||
|
@ -378,6 +338,10 @@ restart:
|
|||
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
||||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
||||
|
||||
return ak8963config.write(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again
|
||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
||||
state = CHECK_STATUS;
|
||||
return true;
|
||||
#else
|
||||
return ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -64,7 +64,7 @@ bool ak8975detect(mag_t *mag)
|
|||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
|
||||
if (!ack || sig != 'H') // 0x48 / 01001000 / 'H'
|
||||
return false;
|
||||
|
||||
|
@ -86,24 +86,24 @@ void ak8975Init()
|
|||
|
||||
UNUSED(ack);
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
|
||||
delay(20);
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
|
||||
delay(10);
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
|
||||
delay(10);
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
|
||||
delay(10);
|
||||
|
||||
// Clear status registers
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
|
||||
// Trigger first measurement
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
|
||||
}
|
||||
|
||||
#define BIT_STATUS1_REG_DATA_READY (1 << 0)
|
||||
|
@ -118,13 +118,13 @@ bool ak8975Read(int16_t *magData)
|
|||
uint8_t status;
|
||||
uint8_t buf[6];
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
|
||||
if (!ack || (status & BIT_STATUS1_REG_DATA_READY) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#if 1 // USE_I2C_SINGLE_BYTE_READS
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
|
||||
#else
|
||||
for (uint8_t i = 0; i < 6; i++) {
|
||||
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL + i, 1, &buf[i]); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
|
||||
|
@ -134,7 +134,7 @@ bool ak8975Read(int16_t *magData)
|
|||
}
|
||||
#endif
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
|
||||
if (!ack) {
|
||||
return false;
|
||||
}
|
||||
|
@ -152,6 +152,6 @@ bool ak8975Read(int16_t *magData)
|
|||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * 4;
|
||||
|
||||
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
|
||||
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -204,7 +204,7 @@ bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
|
|||
|
||||
hmc5883Config = hmc5883ConfigToUse;
|
||||
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
|
||||
ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
|
||||
if (!ack || sig != 'H')
|
||||
return false;
|
||||
|
||||
|
@ -241,15 +241,15 @@ void hmc5883lInit(void)
|
|||
}
|
||||
|
||||
delay(50);
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
|
||||
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
|
||||
// The new gain setting is effective from the second measurement and on.
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
|
||||
delay(100);
|
||||
hmc5883lRead(magADC);
|
||||
|
||||
for (i = 0; i < 10; i++) { // Collect 10 samples
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
|
||||
delay(50);
|
||||
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
|
||||
|
||||
|
@ -267,9 +267,9 @@ void hmc5883lInit(void)
|
|||
}
|
||||
|
||||
// Apply the negative bias. (Same gain)
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
|
||||
for (i = 0; i < 10; i++) {
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
|
||||
delay(50);
|
||||
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
|
||||
|
||||
|
@ -291,9 +291,9 @@ void hmc5883lInit(void)
|
|||
magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]);
|
||||
|
||||
// leave test mode
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
|
||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
|
||||
delay(100);
|
||||
|
||||
if (!bret) { // Something went wrong so get a best guess
|
||||
|
@ -309,7 +309,7 @@ bool hmc5883lRead(int16_t *magData)
|
|||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
|
||||
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
|
||||
if (!ack) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -32,7 +32,7 @@ static dmaHandlers_t dmaHandlers;
|
|||
|
||||
void dmaNoOpHandler(DMA_Stream_TypeDef *stream)
|
||||
{
|
||||
UNUSED(stream);
|
||||
UNUSED(stream);
|
||||
}
|
||||
|
||||
void DMA1_Stream2_IRQHandler(void)
|
||||
|
|
|
@ -95,7 +95,7 @@ static void m25p16_writeEnable()
|
|||
|
||||
static uint8_t m25p16_readStatus()
|
||||
{
|
||||
uint8_t command[2] = {M25P16_INSTRUCTION_READ_STATUS_REG, 0};
|
||||
uint8_t command[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
|
||||
uint8_t in[2];
|
||||
|
||||
ENABLE_M25P16;
|
||||
|
@ -134,7 +134,7 @@ bool m25p16_waitForReady(uint32_t timeoutMillis)
|
|||
*/
|
||||
static bool m25p16_readIdentification()
|
||||
{
|
||||
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0};
|
||||
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
|
||||
uint8_t in[4];
|
||||
uint32_t chipID;
|
||||
|
||||
|
@ -210,7 +210,7 @@ bool m25p16_init()
|
|||
|
||||
#ifndef M25P16_SPI_SHARED
|
||||
//Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz
|
||||
spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(M25P16_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||
#endif
|
||||
|
||||
return m25p16_readIdentification();
|
||||
|
|
|
@ -31,15 +31,15 @@ static const IO_t pin = DEFIO_IO(INVERTER);
|
|||
|
||||
void initInverter(void)
|
||||
{
|
||||
IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterSet(false);
|
||||
}
|
||||
|
||||
void inverterSet(bool on)
|
||||
{
|
||||
IOWrite(pin, on);
|
||||
IOWrite(pin, on);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -55,11 +55,11 @@ uint8_t max7456_send(uint8_t add, uint8_t data) {
|
|||
}
|
||||
|
||||
|
||||
void max7456_init(uint8_t video_system) {
|
||||
void max7456_init(uint8_t video_system)
|
||||
{
|
||||
uint8_t max_screen_rows;
|
||||
uint8_t srdata = 0;
|
||||
uint16_t x;
|
||||
char buf[LINE];
|
||||
|
||||
#ifdef MAX7456_SPI_CS_PIN
|
||||
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
|
||||
|
@ -68,7 +68,7 @@ void max7456_init(uint8_t video_system) {
|
|||
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
|
||||
|
||||
//Minimum spi clock period for max7456 is 100ns (10Mhz)
|
||||
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
|
||||
delay(1000);
|
||||
// force soft reset on Max7456
|
||||
|
@ -77,10 +77,10 @@ void max7456_init(uint8_t video_system) {
|
|||
delay(100);
|
||||
|
||||
srdata = max7456_send(0xA0, 0xFF);
|
||||
if ((0x01 & srdata) == 0x01){ //PAL
|
||||
if ((0x01 & srdata) == 0x01) { //PAL
|
||||
video_signal_type = VIDEO_MODE_PAL;
|
||||
}
|
||||
else if((0x02 & srdata) == 0x02){ //NTSC
|
||||
else if ((0x02 & srdata) == 0x02) { //NTSC
|
||||
video_signal_type = VIDEO_MODE_NTSC;
|
||||
}
|
||||
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
#include "pwm_rx.h"
|
||||
#include "pwm_mapping.h"
|
||||
|
||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
|
||||
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
||||
|
@ -306,7 +306,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
||||
}
|
||||
#endif
|
||||
|
@ -327,7 +327,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse);
|
||||
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
|
||||
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate);
|
||||
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM;
|
||||
} else {
|
||||
pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||
|
|
|
@ -30,17 +30,14 @@
|
|||
#error Invalid motor/servo/port configuration
|
||||
#endif
|
||||
|
||||
|
||||
#define PULSE_1MS (1000) // 1ms pulse width
|
||||
|
||||
#define MAX_INPUTS 8
|
||||
|
||||
#define PWM_TIMER_MHZ 1
|
||||
|
||||
#define PWM_BRUSHED_TIMER_MHZ 8
|
||||
#define MULTISHOT_TIMER_MHZ 72
|
||||
#define ONESHOT42_TIMER_MHZ 24
|
||||
#define ONESHOT125_TIMER_MHZ 8
|
||||
#define PWM_BRUSHED_TIMER_MHZ 24
|
||||
#define MULTISHOT_TIMER_MHZ 72
|
||||
#define ONESHOT42_TIMER_MHZ 24
|
||||
#define ONESHOT125_TIMER_MHZ 8
|
||||
|
||||
typedef struct sonarIOConfig_s {
|
||||
ioTag_t triggerTag;
|
||||
|
@ -81,19 +78,19 @@ typedef struct drv_pwm_config_s {
|
|||
} drv_pwm_config_t;
|
||||
|
||||
enum {
|
||||
MAP_TO_PPM_INPUT = 1,
|
||||
MAP_TO_PPM_INPUT = 1,
|
||||
MAP_TO_PWM_INPUT,
|
||||
MAP_TO_MOTOR_OUTPUT,
|
||||
MAP_TO_SERVO_OUTPUT,
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
PWM_PF_NONE = 0,
|
||||
PWM_PF_MOTOR = (1 << 0),
|
||||
PWM_PF_SERVO = (1 << 1),
|
||||
PWM_PF_MOTOR_MODE_BRUSHED = (1 << 2),
|
||||
PWM_PF_OUTPUT_PROTOCOL_PWM = (1 << 3),
|
||||
PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4)
|
||||
PWM_PF_NONE = 0,
|
||||
PWM_PF_MOTOR = (1 << 0),
|
||||
PWM_PF_SERVO = (1 << 1),
|
||||
PWM_PF_MOTOR_MODE_BRUSHED = (1 << 2),
|
||||
PWM_PF_OUTPUT_PROTOCOL_PWM = (1 << 3),
|
||||
PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4)
|
||||
} pwmPortFlags_e;
|
||||
|
||||
enum {PWM_INVERTED = 1};
|
||||
|
|
|
@ -170,12 +170,11 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
|
|||
uint8_t index;
|
||||
TIM_TypeDef *lastTimerPtr = NULL;
|
||||
|
||||
for(index = 0; index < motorCount; index++){
|
||||
for (index = 0; index < motorCount; index++) {
|
||||
|
||||
// Force the timer to overflow if it's the first motor to output, or if we change timers
|
||||
if(motors[index]->tim != lastTimerPtr){
|
||||
if (motors[index]->tim != lastTimerPtr) {
|
||||
lastTimerPtr = motors[index]->tim;
|
||||
|
||||
timerForceOverflow(motors[index]->tim);
|
||||
}
|
||||
|
||||
|
@ -185,10 +184,10 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
|
|||
}
|
||||
}
|
||||
|
||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
|
||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate)
|
||||
{
|
||||
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
|
||||
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, idlePulse);
|
||||
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0);
|
||||
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
|
||||
}
|
||||
|
||||
|
|
|
@ -339,8 +339,8 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture
|
|||
|
||||
static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode)
|
||||
{
|
||||
IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT);
|
||||
IOConfigGPIO(IOGetByTag(pin), mode);
|
||||
IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT);
|
||||
IOConfigGPIO(IOGetByTag(pin), mode);
|
||||
}
|
||||
|
||||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||
|
|
|
@ -23,7 +23,9 @@ typedef enum {
|
|||
OWNER_FLASH,
|
||||
OWNER_USB,
|
||||
OWNER_BEEPER,
|
||||
OWNER_OSD
|
||||
OWNER_OSD,
|
||||
OWNER_BARO,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_t;
|
||||
|
||||
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)
|
||||
|
|
|
@ -56,7 +56,7 @@ void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count)
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t serialRxBytesWaiting(serialPort_t *instance)
|
||||
uint32_t serialRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
return instance->vTable->serialTotalRxWaiting(instance);
|
||||
}
|
||||
|
|
|
@ -62,7 +62,7 @@ typedef struct serialPort_s {
|
|||
struct serialPortVTable {
|
||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||
|
||||
uint8_t (*serialTotalRxWaiting)(serialPort_t *instance);
|
||||
uint32_t (*serialTotalRxWaiting)(serialPort_t *instance);
|
||||
uint8_t (*serialTotalTxFree)(serialPort_t *instance);
|
||||
|
||||
uint8_t (*serialRead)(serialPort_t *instance);
|
||||
|
@ -81,7 +81,7 @@ struct serialPortVTable {
|
|||
};
|
||||
|
||||
void serialWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t serialRxBytesWaiting(serialPort_t *instance);
|
||||
uint32_t serialRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t serialTxBytesFree(serialPort_t *instance);
|
||||
void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count);
|
||||
uint8_t serialRead(serialPort_t *instance);
|
||||
|
|
|
@ -96,7 +96,7 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state)
|
|||
if (state) {
|
||||
IOHi(softSerial->txIO);
|
||||
} else {
|
||||
IOLo(softSerial->txIO);
|
||||
IOLo(softSerial->txIO);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -408,7 +408,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
|||
}
|
||||
}
|
||||
|
||||
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
|
||||
uint32_t softSerialRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
if ((instance->mode & MODE_RX) == 0) {
|
||||
return 0;
|
||||
|
|
|
@ -28,7 +28,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
|
||||
// serialPort API
|
||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t softSerialRxBytesWaiting(serialPort_t *instance);
|
||||
uint32_t softSerialRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t softSerialTxBytesFree(serialPort_t *instance);
|
||||
uint8_t softSerialReadByte(serialPort_t *instance);
|
||||
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
|
|
|
@ -165,7 +165,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||
#endif
|
||||
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
|
||||
|
||||
|
||||
#ifdef STM32F4
|
||||
DMA_InitStructure.DMA_Channel = s->rxDMAChannel;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||
|
@ -176,7 +176,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
DMA_Cmd(s->rxDMAStream, ENABLE);
|
||||
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
|
||||
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream);
|
||||
#else
|
||||
#else
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
|
||||
|
@ -228,7 +228,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
DMA_Init(s->txDMAStream, &DMA_InitStructure);
|
||||
DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE);
|
||||
DMA_SetCurrDataCounter(s->txDMAStream, 0);
|
||||
#else
|
||||
#else
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_DeInit(s->txDMAChannel);
|
||||
|
@ -292,7 +292,7 @@ void uartStartTxDMA(uartPort_t *s)
|
|||
#endif
|
||||
}
|
||||
|
||||
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance)
|
||||
uint32_t uartTotalRxBytesWaiting(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t*)instance;
|
||||
#ifdef STM32F4
|
||||
|
|
|
@ -38,15 +38,15 @@
|
|||
|
||||
typedef struct {
|
||||
serialPort_t port;
|
||||
|
||||
|
||||
#ifdef STM32F4
|
||||
DMA_Stream_TypeDef *rxDMAStream;
|
||||
DMA_Stream_TypeDef *txDMAStream;
|
||||
uint32_t rxDMAChannel;
|
||||
uint32_t txDMAChannel;
|
||||
DMA_Stream_TypeDef *rxDMAStream;
|
||||
DMA_Stream_TypeDef *txDMAStream;
|
||||
uint32_t rxDMAChannel;
|
||||
uint32_t txDMAChannel;
|
||||
#else
|
||||
DMA_Channel_TypeDef *rxDMAChannel;
|
||||
DMA_Channel_TypeDef *txDMAChannel;
|
||||
DMA_Channel_TypeDef *rxDMAChannel;
|
||||
DMA_Channel_TypeDef *txDMAChannel;
|
||||
#endif
|
||||
|
||||
uint32_t rxDMAIrq;
|
||||
|
@ -65,7 +65,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
|||
|
||||
// serialPort API
|
||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance);
|
||||
uint32_t uartTotalRxBytesWaiting(serialPort_t *instance);
|
||||
uint8_t uartTotalTxBytesFree(serialPort_t *instance);
|
||||
uint8_t uartRead(serialPort_t *instance);
|
||||
void uartSetBaudRate(serialPort_t *s, uint32_t baudRate);
|
||||
|
|
|
@ -365,22 +365,22 @@ void DMA2_Stream7_IRQHandler(void)
|
|||
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7);
|
||||
}
|
||||
}
|
||||
|
||||
// USART1 Rx/Tx IRQ Handler
|
||||
|
@ -402,30 +402,30 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
void DMA1_Stream6_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6);
|
||||
}
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6);
|
||||
}
|
||||
}
|
||||
|
||||
void USART2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
||||
usartIrqHandler(s);
|
||||
usartIrqHandler(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -442,22 +442,22 @@ void DMA1_Stream3_IRQHandler(void)
|
|||
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF3))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF3);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF3);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF3)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF3);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF3);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF3);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF3)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF3);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF3)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF3);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF3)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF3);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF3)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF3);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF3)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF3);
|
||||
}
|
||||
}
|
||||
|
||||
void USART3_IRQHandler(void)
|
||||
|
@ -480,22 +480,22 @@ void DMA1_Stream4_IRQHandler(void)
|
|||
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF4))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF4);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF4);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF4)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF4);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF4);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF4);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF4)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF4);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF4)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF4);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF4)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF4);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF4)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF4);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF4)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF4);
|
||||
}
|
||||
}
|
||||
|
||||
void UART4_IRQHandler(void)
|
||||
|
@ -518,22 +518,22 @@ void DMA1_Stream7_IRQHandler(void)
|
|||
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7);
|
||||
}
|
||||
}
|
||||
|
||||
void UART5_IRQHandler(void)
|
||||
|
@ -556,22 +556,22 @@ void DMA2_Stream6_IRQHandler(void)
|
|||
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
||||
if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6))
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6);
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6);
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6);
|
||||
}
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6);
|
||||
}
|
||||
if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET)
|
||||
{
|
||||
DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6);
|
||||
}
|
||||
}
|
||||
|
||||
void USART6_IRQHandler(void)
|
||||
|
|
|
@ -66,11 +66,11 @@ static bool isUsbVcpTransmitBufferEmpty(serialPort_t *instance)
|
|||
return true;
|
||||
}
|
||||
|
||||
static uint8_t usbVcpAvailable(serialPort_t *instance)
|
||||
static uint32_t usbVcpAvailable(serialPort_t *instance)
|
||||
{
|
||||
UNUSED(instance);
|
||||
|
||||
return receiveLength & 0xFF; // FIXME use uint32_t return type everywhere
|
||||
return receiveLength;
|
||||
}
|
||||
|
||||
static uint8_t usbVcpRead(serialPort_t *instance)
|
||||
|
@ -117,10 +117,11 @@ static bool usbVcpFlush(vcpPort_t *port)
|
|||
if (count == 0) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (!usbIsConnected() || !usbIsConfigured()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
uint32_t txed;
|
||||
uint32_t start = millis();
|
||||
|
||||
|
@ -147,7 +148,7 @@ static void usbVcpBeginWrite(serialPort_t *instance)
|
|||
port->buffering = true;
|
||||
}
|
||||
|
||||
uint8_t usbTxBytesFree()
|
||||
uint8_t usbTxBytesFree()
|
||||
{
|
||||
// Because we block upon transmit and don't buffer bytes, our "buffer" capacity is effectively unlimited.
|
||||
return 255;
|
||||
|
@ -182,12 +183,12 @@ serialPort_t *usbVcpOpen(void)
|
|||
#ifdef STM32F4
|
||||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_IO);
|
||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_IO);
|
||||
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
|
||||
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
|
||||
#else
|
||||
Set_System();
|
||||
Set_USBClock();
|
||||
USB_Interrupts_Config();
|
||||
USB_Init();
|
||||
Set_System();
|
||||
Set_USBClock();
|
||||
USB_Interrupts_Config();
|
||||
USB_Init();
|
||||
#endif
|
||||
|
||||
s = &vcpPort;
|
||||
|
|
|
@ -92,9 +92,9 @@ void hcsr04_init(sonarRange_t *sonarRange)
|
|||
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
|
||||
|
||||
#ifdef USE_EXTI
|
||||
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
|
||||
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
|
||||
EXTIEnable(echoIO, true);
|
||||
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
|
||||
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
|
||||
EXTIEnable(echoIO, true);
|
||||
#endif
|
||||
|
||||
lastMeasurementAt = millis() - 60; // force 1st measurement in hcsr04_get_distance()
|
||||
|
|
|
@ -39,31 +39,31 @@ static bool beeperInverted = false;
|
|||
void systemBeep(bool onoff)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(onoff);
|
||||
UNUSED(onoff);
|
||||
#else
|
||||
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
||||
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
||||
#endif
|
||||
}
|
||||
|
||||
void systemBeepToggle(void)
|
||||
{
|
||||
#ifdef BEEPER
|
||||
IOToggle(beeperIO);
|
||||
IOToggle(beeperIO);
|
||||
#endif
|
||||
}
|
||||
|
||||
void beeperInit(const beeperConfig_t *config)
|
||||
{
|
||||
#ifndef BEEPER
|
||||
UNUSED(config);
|
||||
UNUSED(config);
|
||||
#else
|
||||
beeperIO = IOGetByTag(config->ioTag);
|
||||
beeperInverted = config->isInverted;
|
||||
beeperIO = IOGetByTag(config->ioTag);
|
||||
beeperInverted = config->isInverted;
|
||||
|
||||
if (beeperIO) {
|
||||
IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP);
|
||||
}
|
||||
systemBeep(false);
|
||||
if (beeperIO) {
|
||||
IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT);
|
||||
IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP);
|
||||
}
|
||||
systemBeep(false);
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -30,9 +30,9 @@
|
|||
#endif
|
||||
|
||||
typedef struct beeperConfig_s {
|
||||
ioTag_t ioTag;
|
||||
unsigned isInverted : 1;
|
||||
unsigned isOD : 1;
|
||||
ioTag_t ioTag;
|
||||
unsigned isInverted : 1;
|
||||
unsigned isOD : 1;
|
||||
} beeperConfig_t;
|
||||
|
||||
void systemBeep(bool on);
|
||||
|
|
|
@ -25,13 +25,13 @@ uint32_t micros(void);
|
|||
uint32_t millis(void);
|
||||
|
||||
typedef enum {
|
||||
FAILURE_DEVELOPER = 0,
|
||||
FAILURE_MISSING_ACC,
|
||||
FAILURE_ACC_INIT,
|
||||
FAILURE_ACC_INCOMPATIBLE,
|
||||
FAILURE_INVALID_EEPROM_CONTENTS,
|
||||
FAILURE_FLASH_WRITE_FAILED,
|
||||
FAILURE_GYRO_INIT_FAILED
|
||||
FAILURE_DEVELOPER = 0,
|
||||
FAILURE_MISSING_ACC,
|
||||
FAILURE_ACC_INIT,
|
||||
FAILURE_ACC_INCOMPATIBLE,
|
||||
FAILURE_INVALID_EEPROM_CONTENTS,
|
||||
FAILURE_FLASH_WRITE_FAILED,
|
||||
FAILURE_GYRO_INIT_FAILED
|
||||
} failureMode_e;
|
||||
|
||||
// failure
|
||||
|
|
|
@ -45,8 +45,8 @@ void systemReset(void)
|
|||
if (mpuConfiguration.reset)
|
||||
mpuConfiguration.reset();
|
||||
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void systemResetToBootloader(void)
|
||||
|
@ -54,10 +54,10 @@ void systemResetToBootloader(void)
|
|||
if (mpuConfiguration.reset)
|
||||
mpuConfiguration.reset();
|
||||
|
||||
*((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX
|
||||
*((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX
|
||||
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void enableGPIOPowerUsageAndNoiseReductions(void)
|
||||
|
@ -82,7 +82,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
|
|||
RCC_AHB1Periph_BKPSRAM |
|
||||
RCC_AHB1Periph_DMA1 |
|
||||
RCC_AHB1Periph_DMA2 |
|
||||
0, ENABLE
|
||||
0, ENABLE
|
||||
);
|
||||
|
||||
RCC_AHB2PeriphClockCmd(0, ENABLE);
|
||||
|
@ -172,25 +172,25 @@ void systemInit(void)
|
|||
SetSysClock();
|
||||
|
||||
// Configure NVIC preempt/priority groups
|
||||
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
|
||||
NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING);
|
||||
|
||||
// cache RCC->CSR value to use it in isMPUSoftreset() and others
|
||||
cachedRccCsrValue = RCC->CSR;
|
||||
cachedRccCsrValue = RCC->CSR;
|
||||
|
||||
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
||||
extern void *isr_vector_table_base;
|
||||
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
|
||||
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
|
||||
extern void *isr_vector_table_base;
|
||||
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
|
||||
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
|
||||
|
||||
RCC_ClearFlag();
|
||||
RCC_ClearFlag();
|
||||
|
||||
enableGPIOPowerUsageAndNoiseReductions();
|
||||
enableGPIOPowerUsageAndNoiseReductions();
|
||||
|
||||
// Init cycle counter
|
||||
cycleCounterInit();
|
||||
cycleCounterInit();
|
||||
|
||||
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
|
||||
// SysTick
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs));
|
||||
// SysTick
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
}
|
||||
|
||||
|
|
|
@ -17,7 +17,6 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
@ -26,7 +25,6 @@
|
|||
|
||||
#include "nvic.h"
|
||||
|
||||
#include "gpio.h"
|
||||
#include "gpio.h"
|
||||
#include "rcc.h"
|
||||
#include "system.h"
|
||||
|
@ -148,7 +146,7 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
|
|||
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
|
||||
if (timerDefinitions[i].TIMx == tim) {
|
||||
return timerDefinitions[i].rcc;
|
||||
}
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
@ -190,7 +188,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
|||
#else
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
|
||||
#endif
|
||||
|
||||
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
|
||||
|
@ -660,7 +658,7 @@ void timerInit(void)
|
|||
IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// initialize timer channel structures
|
||||
for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||
timerChannelInfo[i].type = TYPE_FREE;
|
||||
|
|
|
@ -47,9 +47,10 @@ typedef uint32_t timCCER_t;
|
|||
typedef uint32_t timSR_t;
|
||||
typedef uint32_t timCNT_t;
|
||||
#else
|
||||
# error "Unknown CPU defined"
|
||||
#error "Unknown CPU defined"
|
||||
#endif
|
||||
|
||||
|
||||
// use different types from capture and overflow - multiple overflow handlers are implemented as linked list
|
||||
struct timerCCHandlerRec_s;
|
||||
struct timerOvrHandlerRec_s;
|
||||
|
|
|
@ -68,8 +68,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
|
|||
tmp = (uint32_t) TIMx;
|
||||
tmp += CCMR_OFFSET;
|
||||
|
||||
if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
|
||||
{
|
||||
if ((TIM_Channel == TIM_Channel_1) || (TIM_Channel == TIM_Channel_3)) {
|
||||
tmp += (TIM_Channel>>1);
|
||||
|
||||
/* Reset the OCxM bits in the CCMRx register */
|
||||
|
@ -77,9 +76,7 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t
|
|||
|
||||
/* Configure the OCxM bits in the CCMRx register */
|
||||
*(__IO uint32_t *) tmp |= TIM_OCMode;
|
||||
}
|
||||
else
|
||||
{
|
||||
} else {
|
||||
tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1;
|
||||
|
||||
/* Reset the OCxM bits in the CCMRx register */
|
||||
|
|
|
@ -133,7 +133,7 @@ static uint32_t reverse32(uint32_t in)
|
|||
bool rtc6705Init(void)
|
||||
{
|
||||
DISABLE_RTC6705;
|
||||
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
|
||||
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
|
||||
return rtc6705IsReady();
|
||||
}
|
||||
|
||||
|
|
|
@ -463,7 +463,7 @@ static const char * const lookupTableSuperExpoYaw[] = {
|
|||
"OFF", "ON", "ALWAYS"
|
||||
};
|
||||
|
||||
static const char * const lookupTableFastPwm[] = {
|
||||
static const char * const lookupTablePwmProtocol[] = {
|
||||
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
|
||||
};
|
||||
|
||||
|
@ -525,7 +525,7 @@ static const lookupTableEntry_t lookupTables[] = {
|
|||
{ lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
|
||||
{ lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
|
||||
{ lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
|
||||
{ lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) },
|
||||
{ lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
|
||||
{ lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) },
|
||||
#ifdef OSD
|
||||
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
|
||||
|
@ -1902,10 +1902,11 @@ static void dumpValues(uint16_t valueSection)
|
|||
cliPrintf("set %s = ", valueTable[i].name);
|
||||
cliPrintVar(value, 0);
|
||||
cliPrint("\r\n");
|
||||
|
||||
#ifdef STM32F4
|
||||
delayMicroseconds(1000);
|
||||
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1979,6 +1980,9 @@ static void cliDump(char *cmdline)
|
|||
if (yaw < 0)
|
||||
cliWrite(' ');
|
||||
cliPrintf("%s\r\n", ftoa(yaw, buf));
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
@ -2000,6 +2004,10 @@ static void cliDump(char *cmdline)
|
|||
masterConfig.customServoMixer[i].max,
|
||||
masterConfig.customServoMixer[i].box
|
||||
);
|
||||
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -2012,12 +2020,18 @@ static void cliDump(char *cmdline)
|
|||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
cliPrintf("feature -%s\r\n", featureNames[i]);
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
for (i = 0; ; i++) { // reenable what we want.
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
if (mask & (1 << i))
|
||||
cliPrintf("feature %s\r\n", featureNames[i]);
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -2077,6 +2091,9 @@ static void cliDump(char *cmdline)
|
|||
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
|
||||
if (servoDirection(i, channel) < 0) {
|
||||
cliPrintf("smix reverse %d %d r\r\n", i , channel);
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2109,6 +2126,9 @@ static void cliDump(char *cmdline)
|
|||
|
||||
changeControlRateProfile(currentRateIndex);
|
||||
cliRateProfile("");
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
|
||||
cliPrint("\r\n# restore original profile selection\r\n");
|
||||
|
@ -2133,7 +2153,8 @@ static void cliDump(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
void cliDumpProfile(uint8_t profileIndex) {
|
||||
void cliDumpProfile(uint8_t profileIndex)
|
||||
{
|
||||
if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
|
||||
return;
|
||||
|
||||
|
@ -2148,7 +2169,8 @@ void cliDumpProfile(uint8_t profileIndex) {
|
|||
cliRateProfile("");
|
||||
}
|
||||
|
||||
void cliDumpRateProfile(uint8_t rateProfileIndex) {
|
||||
void cliDumpRateProfile(uint8_t rateProfileIndex)
|
||||
{
|
||||
if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
|
||||
return;
|
||||
|
||||
|
@ -2541,12 +2563,12 @@ static void cliRateProfile(char *cmdline) {
|
|||
}
|
||||
}
|
||||
|
||||
static void cliReboot(void) {
|
||||
static void cliReboot(void)
|
||||
{
|
||||
cliPrint("\r\nRebooting");
|
||||
bufWriterFlush(cliWriter);
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
|
||||
|
@ -2653,7 +2675,7 @@ static void cliPrintVarRange(const clivalue_t *var)
|
|||
{
|
||||
switch (var->type & VALUE_MODE_MASK) {
|
||||
case (MODE_DIRECT): {
|
||||
cliPrintf("Allowed range: %d - %d\n", var->config.minmax.min, var->config.minmax.max);
|
||||
cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
|
||||
}
|
||||
break;
|
||||
case (MODE_LOOKUP): {
|
||||
|
@ -2665,7 +2687,7 @@ static void cliPrintVarRange(const clivalue_t *var)
|
|||
cliPrint(",");
|
||||
cliPrintf(" %s", tableEntry->values[i]);
|
||||
}
|
||||
cliPrint("\n");
|
||||
cliPrint("\r\n");
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -2717,6 +2739,10 @@ static void cliSet(char *cmdline)
|
|||
cliPrintf("%s = ", valueTable[i].name);
|
||||
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
|
||||
cliPrint("\r\n");
|
||||
|
||||
#ifdef USE_SLOW_SERIAL_CLI
|
||||
delay(2);
|
||||
#endif
|
||||
}
|
||||
} else if ((eqptr = strstr(cmdline, "=")) != NULL) {
|
||||
// has equals
|
||||
|
@ -2891,14 +2917,14 @@ static void cliTasks(char *cmdline)
|
|||
subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
|
||||
if (masterConfig.pid_process_denom > 1) {
|
||||
taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
|
||||
cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
|
||||
} else {
|
||||
taskFrequency = subTaskFrequency;
|
||||
cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
|
||||
}
|
||||
} else {
|
||||
taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
|
||||
cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
|
||||
}
|
||||
|
||||
cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
|
||||
|
@ -2909,7 +2935,7 @@ static void cliTasks(char *cmdline)
|
|||
cliPrintf("%dms", taskTotalTime);
|
||||
}
|
||||
|
||||
if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
|
||||
if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n - - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
|
||||
cliPrintf("\r\n", taskTotalTime);
|
||||
}
|
||||
}
|
||||
|
@ -3038,7 +3064,7 @@ void cliProcess(void)
|
|||
}
|
||||
}
|
||||
|
||||
const char * const ownerNames[] = {
|
||||
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||
"FREE",
|
||||
"PWM IN",
|
||||
"PPM IN",
|
||||
|
@ -3060,6 +3086,8 @@ const char * const ownerNames[] = {
|
|||
"FLASH",
|
||||
"USB",
|
||||
"BEEPER",
|
||||
"OSD",
|
||||
"BARO",
|
||||
};
|
||||
|
||||
static void cliResource(char *cmdline)
|
||||
|
|
|
@ -1272,11 +1272,10 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
serialize16(currentProfile->pidProfile.yaw_lpf_hz);
|
||||
break;
|
||||
case MSP_ADVANCED_TUNING:
|
||||
headSerialReply(4 * 2 + 2);
|
||||
headSerialReply(3 * 2 + 2);
|
||||
serialize16(currentProfile->pidProfile.rollPitchItermIgnoreRate);
|
||||
serialize16(currentProfile->pidProfile.yawItermIgnoreRate);
|
||||
serialize16(currentProfile->pidProfile.yaw_p_limit);
|
||||
serialize16(masterConfig.rxConfig.airModeActivateThreshold);
|
||||
serialize8(currentProfile->pidProfile.deltaMethod);
|
||||
serialize8(masterConfig.batteryConfig.vbatPidCompensation);
|
||||
break;
|
||||
|
@ -1516,7 +1515,7 @@ static bool processInCommand(void)
|
|||
break;
|
||||
|
||||
case MSP_SET_RESET_CURR_PID:
|
||||
//resetPidProfile(¤tProfile->pidProfile);
|
||||
resetPidProfile(¤tProfile->pidProfile);
|
||||
break;
|
||||
|
||||
case MSP_SET_SENSOR_ALIGNMENT:
|
||||
|
@ -1857,6 +1856,7 @@ static bool processInCommand(void)
|
|||
currentProfile->pidProfile.yawItermIgnoreRate = read16();
|
||||
currentProfile->pidProfile.yaw_p_limit = read16();
|
||||
currentProfile->pidProfile.deltaMethod = read8();
|
||||
masterConfig.batteryConfig.vbatPidCompensation = read8();
|
||||
break;
|
||||
case MSP_SET_SPECIAL_PARAMETERS:
|
||||
currentControlRateProfile->rcYawRate8 = read8();
|
||||
|
@ -1969,7 +1969,6 @@ void mspProcess(void)
|
|||
if (isRebootScheduled) {
|
||||
waitForSerialPortToFinishTransmitting(candidatePort->port);
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
// On real flight controllers, systemReset() will do a soft reset of the device,
|
||||
// reloading the program. But to support offline testing this flag needs to be
|
||||
// cleared so that the software doesn't continuously attempt to reboot itself.
|
||||
|
|
|
@ -17,11 +17,11 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -153,9 +153,6 @@ static uint8_t systemState = SYSTEM_STATE_INITIALISING;
|
|||
|
||||
void init(void)
|
||||
{
|
||||
uint8_t i;
|
||||
drv_pwm_config_t pwm_params;
|
||||
|
||||
printfSupportInit();
|
||||
|
||||
initEEPROM();
|
||||
|
@ -260,6 +257,7 @@ void init(void)
|
|||
mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
|
||||
#endif
|
||||
|
||||
drv_pwm_config_t pwm_params;
|
||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||
|
||||
#ifdef SONAR
|
||||
|
@ -314,7 +312,7 @@ void init(void)
|
|||
}
|
||||
|
||||
bool use_unsyncedPwm = masterConfig.use_unsyncedPwm;
|
||||
|
||||
|
||||
// Configurator feature abused for enabling Fast PWM
|
||||
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED);
|
||||
pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol;
|
||||
|
@ -322,7 +320,9 @@ void init(void)
|
|||
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
|
||||
if (feature(FEATURE_3D))
|
||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
|
||||
if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) {
|
||||
featureClear(FEATURE_3D);
|
||||
pwm_params.idlePulse = 0; // brushed motors
|
||||
use_unsyncedPwm = false;
|
||||
}
|
||||
|
@ -331,13 +331,17 @@ void init(void)
|
|||
#endif
|
||||
pwmRxInit(masterConfig.inputFilteringMode);
|
||||
|
||||
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
|
||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
|
||||
|
||||
mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm);
|
||||
|
||||
/*
|
||||
// TODO is this needed here? enables at the end
|
||||
if (!feature(FEATURE_ONESHOT125))
|
||||
motorControlEnable = true;
|
||||
|
||||
*/
|
||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||
|
||||
#ifdef BEEPER
|
||||
|
@ -483,12 +487,12 @@ void init(void)
|
|||
#endif
|
||||
|
||||
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,
|
||||
masterConfig.acc_hardware,
|
||||
masterConfig.mag_hardware,
|
||||
masterConfig.baro_hardware,
|
||||
masterConfig.mag_declination,
|
||||
masterConfig.gyro_lpf,
|
||||
masterConfig.gyro_sync_denom)) {
|
||||
masterConfig.acc_hardware,
|
||||
masterConfig.mag_hardware,
|
||||
masterConfig.baro_hardware,
|
||||
masterConfig.mag_declination,
|
||||
masterConfig.gyro_lpf,
|
||||
masterConfig.gyro_sync_denom)) {
|
||||
// if gyro was not detected due to whatever reason, we give up now.
|
||||
failureMode(FAILURE_MISSING_ACC);
|
||||
}
|
||||
|
@ -499,7 +503,7 @@ void init(void)
|
|||
LED0_OFF;
|
||||
LED2_OFF;
|
||||
|
||||
for (i = 0; i < 10; i++) {
|
||||
for (int i = 0; i < 10; i++) {
|
||||
LED1_TOGGLE;
|
||||
LED0_TOGGLE;
|
||||
delay(25);
|
||||
|
@ -683,7 +687,7 @@ void processLoopback(void) {
|
|||
#define processLoopback()
|
||||
#endif
|
||||
|
||||
void main_init(void)
|
||||
void main_init(void)
|
||||
{
|
||||
init();
|
||||
|
||||
|
@ -724,7 +728,7 @@ void main_init(void)
|
|||
#endif
|
||||
#ifdef MAG
|
||||
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
||||
#ifdef SPRACINGF3EVO
|
||||
#if defined(USE_SPI) && defined(USE_MAG_AK8963)
|
||||
// fixme temporary solution for AK6983 via slave I2C on MPU9250
|
||||
rescheduleTask(TASK_COMPASS, 1000000 / 40);
|
||||
#endif
|
||||
|
|
|
@ -185,7 +185,7 @@ float calculateRate(int axis, int16_t rc) {
|
|||
}
|
||||
|
||||
|
||||
return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection
|
||||
return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection
|
||||
}
|
||||
|
||||
void processRcCommand(void)
|
||||
|
@ -698,6 +698,8 @@ void subTaskMainSubprocesses(void) {
|
|||
#endif
|
||||
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
||||
updateRcCommands();
|
||||
if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) {
|
||||
if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) {
|
||||
applyAltHold(&masterConfig.airplaneConfig);
|
||||
|
@ -776,7 +778,7 @@ void subTaskMotorUpdate(void)
|
|||
|
||||
uint8_t setPidUpdateCountDown(void) {
|
||||
if (masterConfig.gyro_soft_lpf_hz) {
|
||||
return masterConfig.pid_process_denom - 1;
|
||||
return masterConfig.pid_process_denom - 1;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
|
@ -878,8 +880,10 @@ void taskUpdateRxMain(void)
|
|||
processRx();
|
||||
isRXDataNew = true;
|
||||
|
||||
#if !defined(BARO) && !defined(SONAR)
|
||||
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
||||
updateRcCommands();
|
||||
#endif
|
||||
updateLEDs();
|
||||
|
||||
#ifdef BARO
|
||||
|
|
|
@ -45,7 +45,7 @@ acc_t acc; // acc access functions
|
|||
sensor_align_e accAlign = 0;
|
||||
uint32_t accTargetLooptime;
|
||||
|
||||
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
||||
static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
||||
|
||||
extern uint16_t InflightcalibratingA;
|
||||
extern bool AccInflightCalibrationArmed;
|
||||
|
|
|
@ -20,6 +20,10 @@
|
|||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
int32_t BaroAlt = 0;
|
||||
|
||||
#ifdef BARO
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/barometer.h"
|
||||
|
@ -32,9 +36,6 @@ baro_t baro; // barometer access functions
|
|||
uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
|
||||
int32_t baroPressure = 0;
|
||||
int32_t baroTemperature = 0;
|
||||
int32_t BaroAlt = 0;
|
||||
|
||||
#ifdef BARO
|
||||
|
||||
static int32_t baroGroundAltitude = 0;
|
||||
static int32_t baroGroundPressure = 0;
|
||||
|
|
|
@ -40,12 +40,14 @@
|
|||
#endif
|
||||
|
||||
mag_t mag; // mag access functions
|
||||
int32_t magADC[XYZ_AXIS_COUNT];
|
||||
sensor_align_e magAlign = 0;
|
||||
|
||||
#ifdef MAG
|
||||
|
||||
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
|
||||
|
||||
int32_t magADC[XYZ_AXIS_COUNT];
|
||||
sensor_align_e magAlign = 0;
|
||||
#ifdef MAG
|
||||
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
||||
static uint8_t magInit = 0;
|
||||
|
||||
void compassInit(void)
|
||||
|
@ -57,27 +59,19 @@ void compassInit(void)
|
|||
magInit = 1;
|
||||
}
|
||||
|
||||
#define COMPASS_UPDATE_FREQUENCY_10HZ (1000 * 100)
|
||||
|
||||
void updateCompass(flightDynamicsTrims_t *magZero)
|
||||
{
|
||||
static uint32_t nextUpdateAt, tCal = 0;
|
||||
static uint32_t tCal = 0;
|
||||
static flightDynamicsTrims_t magZeroTempMin;
|
||||
static flightDynamicsTrims_t magZeroTempMax;
|
||||
int16_t magADCRaw[XYZ_AXIS_COUNT];
|
||||
uint32_t axis;
|
||||
|
||||
if ((int32_t)(currentTime - nextUpdateAt) < 0)
|
||||
return;
|
||||
|
||||
nextUpdateAt = currentTime + COMPASS_UPDATE_FREQUENCY_10HZ;
|
||||
|
||||
mag.read(magADCRaw);
|
||||
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) magADC[axis] = magADCRaw[axis];
|
||||
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) magADC[axis] = magADCRaw[axis]; // int32_t copy to work with
|
||||
alignSensors(magADC, magADC, magAlign);
|
||||
|
||||
if (STATE(CALIBRATE_MAG)) {
|
||||
tCal = nextUpdateAt;
|
||||
tCal = currentTime;
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
magZero->raw[axis] = 0;
|
||||
magZeroTempMin.raw[axis] = magADC[axis];
|
||||
|
@ -93,7 +87,7 @@ void updateCompass(flightDynamicsTrims_t *magZero)
|
|||
}
|
||||
|
||||
if (tCal != 0) {
|
||||
if ((nextUpdateAt - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions
|
||||
if ((currentTime - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions
|
||||
LED0_TOGGLE;
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
if (magADC[axis] < magZeroTempMin.raw[axis])
|
||||
|
|
|
@ -56,7 +56,7 @@ void useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz)
|
|||
}
|
||||
|
||||
void initGyroFilterCoefficients(void) {
|
||||
int axis;
|
||||
int axis;
|
||||
if (gyroLpfCutFreq && targetLooptime) { /* Initialisation needs to happen once samplingrate is known */
|
||||
for (axis = 0; axis < 3; axis++) BiQuadNewLpf(gyroLpfCutFreq, &gyroFilterState[axis], targetLooptime);
|
||||
gyroFilterStateIsSet = true;
|
||||
|
@ -137,8 +137,8 @@ static void applyGyroZero(void)
|
|||
|
||||
void gyroUpdate(void)
|
||||
{
|
||||
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
|
||||
int axis;
|
||||
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
|
||||
int axis;
|
||||
|
||||
// range: +/- 8192; +/- 2000 deg/sec
|
||||
if (!gyro.read(gyroADCRaw)) {
|
||||
|
@ -161,10 +161,12 @@ void gyroUpdate(void)
|
|||
if (gyroLpfCutFreq) {
|
||||
if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */
|
||||
|
||||
if (gyroFilterStateIsSet) {
|
||||
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++){
|
||||
for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
if (gyroFilterStateIsSet) {
|
||||
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
|
||||
gyroADC[axis] = lrintf(gyroADCf[axis]);
|
||||
} else {
|
||||
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -216,7 +216,7 @@ bool detectGyro(void)
|
|||
; // fallthrough
|
||||
|
||||
case GYRO_MPU6500:
|
||||
#ifdef USE_GYRO_MPU6500
|
||||
#if defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500)
|
||||
#ifdef USE_GYRO_SPI_MPU6500
|
||||
if (mpu6500GyroDetect(&gyro) || mpu6500SpiGyroDetect(&gyro))
|
||||
#else
|
||||
|
@ -361,7 +361,7 @@ retry:
|
|||
#endif
|
||||
; // fallthrough
|
||||
case ACC_MPU6500:
|
||||
#ifdef USE_ACC_MPU6500
|
||||
#if defined(USE_ACC_MPU6500) || defined(USE_ACC_SPI_MPU6500)
|
||||
#ifdef USE_ACC_SPI_MPU6500
|
||||
if (mpu6500AccDetect(&acc) || mpu6500SpiAccDetect(&acc))
|
||||
#else
|
||||
|
|
|
@ -39,7 +39,7 @@ static IO_t HWDetectPin = IO_NONE;
|
|||
|
||||
void detectHardwareRevision(void)
|
||||
{
|
||||
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
|
||||
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
|
||||
IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT);
|
||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||
|
||||
|
@ -74,4 +74,4 @@ const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
|
|||
else {
|
||||
return &alienFlightF3V2MPUIntExtiConfig;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -45,7 +45,6 @@
|
|||
// Using MPU6050 for the moment.
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
|
||||
#define GYRO_MPU6050_ALIGN CW270_DEG
|
||||
|
@ -53,7 +52,6 @@
|
|||
|
||||
#define ACC
|
||||
#define USE_ACC_MPU6050
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define ACC_MPU6050_ALIGN CW270_DEG
|
||||
|
@ -100,8 +98,8 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
|
||||
|
||||
#define I2C2_SCL_PIN PA9
|
||||
#define I2C2_SDA_PIN PA10
|
||||
#define I2C2_SCL PA9
|
||||
#define I2C2_SDA PA10
|
||||
|
||||
// SPI3
|
||||
// PA15 38 SPI3_NSS
|
||||
|
@ -118,14 +116,8 @@
|
|||
#define USE_ADC
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
#define VBAT_ADC_PIN PA4
|
||||
|
||||
// alternative defaults for AlienFlight F3 target
|
||||
#define ALIENFLIGHT
|
||||
|
@ -139,8 +131,8 @@
|
|||
#define BINDPLUG_PIN PB12
|
||||
|
||||
#define BRUSHED_MOTORS
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -76,8 +76,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM1 - PA8 RC1
|
||||
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM2 - PB0 RC2
|
||||
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM3 - PB1 RC3
|
||||
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM4 - PA14 RC4
|
||||
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM5 - PA15 RC5
|
||||
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM4 - PA14 RC4
|
||||
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM5 - PA15 RC5
|
||||
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM6 - PB8 OUT1
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM7 - PB9 OUT2
|
||||
|
|
|
@ -19,11 +19,6 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "AFF4"
|
||||
|
||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
|
||||
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
|
||||
#define CONFIG_FEATURE_RX_SERIAL
|
||||
#define CONFIG_MSP_PORT 1
|
||||
#define CONFIG_RX_SERIAL_PORT 2
|
||||
|
||||
#define USBD_PRODUCT_STRING "AlienFlight F4"
|
||||
|
||||
|
@ -45,22 +40,14 @@
|
|||
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
#define MPU9250_CS_PIN PA4
|
||||
#define MPU9250_SPI_INSTANCE SPI1
|
||||
|
||||
#define ACC
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define USE_ACC_SPI_MPU9250
|
||||
|
||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||
#define ACC_MPU9250_ALIGN CW270_DEG
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define USE_GYRO_SPI_MPU9250
|
||||
|
||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||
#define GYRO_MPU9250_ALIGN CW270_DEG
|
||||
|
||||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
|
@ -152,18 +139,10 @@
|
|||
|
||||
#define USE_ADC
|
||||
//#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_0
|
||||
|
||||
#define RSSI_ADC_PIN PC4
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_4
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO_PIN PC5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
|
||||
// LED strip configuration using RC5 pin.
|
||||
//#define LED_STRIP
|
||||
|
@ -191,9 +170,11 @@
|
|||
// Hardware bind plug at PB2 (Pin 28)
|
||||
#define BINDPLUG_PIN PB2
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define BRUSHED_MOTORS
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP)
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -4,7 +4,6 @@ FEATURES += SDCARD VCP
|
|||
TARGET_SRC = \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu9250.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8963.c \
|
||||
|
|
|
@ -19,19 +19,14 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "BJF4"
|
||||
|
||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
|
||||
#define CONFIG_FEATURE_RX_SERIAL
|
||||
#define CONFIG_FEATURE_ONESHOT125
|
||||
#define CONFIG_RX_SERIAL_PORT 3
|
||||
|
||||
#define USBD_PRODUCT_STRING "BlueJayF4"
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define USE_EXTI
|
||||
|
||||
#define INVERTER PB15
|
||||
#define INVERTER_USART USART6
|
||||
#define INVERTER PB15
|
||||
#define INVERTER_USART USART6
|
||||
|
||||
#define BEEPER PB7
|
||||
#define BEEPER_INVERTED
|
||||
|
@ -133,14 +128,17 @@
|
|||
#define SPI3_MOSI_PIN PC12
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
#define USE_I2C_PULLUP
|
||||
|
||||
#define USE_ADC
|
||||
#define VBAT_ADC_PIN PC3
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_13
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
|
|
|
@ -28,12 +28,12 @@ const uint16_t multiPWM[] = {
|
|||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
@ -59,26 +59,26 @@ const uint16_t airPWM[] = {
|
|||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPPM_BP6[] = {
|
||||
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
@ -89,9 +89,9 @@ const uint16_t multiPWM_BP6[] = {
|
|||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
|
@ -118,11 +118,11 @@ const uint16_t airPWM_BP6[] = {
|
|||
PWM4 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM5 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
|
||||
PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
|
||||
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
|
|
@ -92,21 +92,12 @@
|
|||
#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOB
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_0
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_8
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA0
|
||||
#define RSSI_ADC_PIN PB0
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
|
||||
|
||||
|
|
|
@ -101,26 +101,11 @@
|
|||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOC
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_6
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOC
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOC
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_8
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOC
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
#define EXTERNAL1_ADC_PIN PC3
|
||||
|
||||
// IO - assuming 303 in 64pin package, TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
|
|
|
@ -55,5 +55,5 @@ void updateHardwareRevision(void)
|
|||
|
||||
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -1545,7 +1545,6 @@ void taskBstMasterProcess(void)
|
|||
bstMasterWriteLoop();
|
||||
if (isRebootScheduled) {
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
resetBstChecker();
|
||||
|
@ -1555,12 +1554,14 @@ void taskBstMasterProcess(void)
|
|||
static uint8_t masterWriteBufferPointer;
|
||||
static uint8_t masterWriteData[DATA_BUFFER_SIZE];
|
||||
|
||||
static void bstMasterStartBuffer(uint8_t address) {
|
||||
static void bstMasterStartBuffer(uint8_t address)
|
||||
{
|
||||
masterWriteData[0] = address;
|
||||
masterWriteBufferPointer = 2;
|
||||
}
|
||||
|
||||
static void bstMasterWrite8(uint8_t data) {
|
||||
static void bstMasterWrite8(uint8_t data)
|
||||
{
|
||||
masterWriteData[masterWriteBufferPointer++] = data;
|
||||
masterWriteData[1] = masterWriteBufferPointer;
|
||||
}
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
||||
#define USE_SPI
|
||||
|
@ -103,16 +103,8 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
#define I2C2_SCL_GPIO GPIOA
|
||||
#define I2C2_SCL_GPIO_AF GPIO_AF_4
|
||||
#define I2C2_SCL_PIN GPIO_Pin_9
|
||||
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
|
||||
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
#define I2C2_SDA_GPIO GPIOA
|
||||
#define I2C2_SDA_GPIO_AF GPIO_AF_4
|
||||
#define I2C2_SDA_PIN GPIO_Pin_10
|
||||
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
#define I2C2_SCL_PIN PA9
|
||||
#define I2C2_SDA_PIN PA10
|
||||
|
||||
#define USE_BST
|
||||
#define BST_DEVICE (BSTDEV_1)
|
||||
|
@ -120,32 +112,17 @@
|
|||
#define BST_CRC_POLYNOM 0xD5
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
#define VBAT_ADC_GPIO GPIOC
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_6
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOC
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOC
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_8
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOC
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
#define EXTERNAL1_ADC_PIN PC3
|
||||
|
||||
#define LED_STRIP
|
||||
#define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG
|
||||
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
|
|
@ -34,44 +34,29 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
// tqfp48 pin 3
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||
#define MPU6500_CS_GPIO GPIOC
|
||||
#define MPU6500_CS_PIN PC14
|
||||
#define MPU6500_SPI_INSTANCE SPI1
|
||||
|
||||
// tqfp48 pin 25
|
||||
#define BMP280_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BMP280_CS_GPIO GPIOB
|
||||
#define BMP280_CS_PIN GPIO_Pin_12
|
||||
#define BMP280_CS_PIN PB12
|
||||
#define BMP280_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define SPI1_GPIO GPIOB
|
||||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
// tqfp48 pin 39
|
||||
#define SPI1_SCK_PIN PB3
|
||||
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
|
||||
// tqfp48 pin 40
|
||||
#define SPI1_MISO_PIN PB4
|
||||
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
|
||||
// tqfp48 pin 41
|
||||
#define SPI1_MOSI_PIN PB5
|
||||
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
|
||||
|
||||
#define SPI2_GPIO GPIOB
|
||||
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
// tqfp48 pin 26
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
|
||||
// tqfp48 pin 27
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
|
||||
// tqfp48 pin 28
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
@ -139,20 +124,9 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
|
||||
// tqfp48 pin 14
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
// tqfp48 pin 15
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
|
||||
// mpu_int definition in sensors/initialisation.c
|
||||
#define USE_EXTI
|
||||
|
|
|
@ -97,22 +97,10 @@
|
|||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOB
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_4
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOA
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOA
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define RSSI_ADC_PIN PA1
|
||||
#define EXTERNAL1_ADC_PIN PA5
|
||||
|
||||
//#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
|
|
|
@ -11,6 +11,7 @@ TARGET_SRC = \
|
|||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu3050.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer_bmp085.c \
|
||||
|
|
|
@ -25,9 +25,9 @@
|
|||
#define USE_EXTI
|
||||
#define CONFIG_PREFER_ACC_ON
|
||||
|
||||
#define LED0 PC14
|
||||
#define LED0 PC14
|
||||
|
||||
#define BEEPER PC15
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect
|
||||
|
@ -150,25 +150,13 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOA
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3
|
||||
#define VBAT_ADC_PIN PA0
|
||||
#define RSSI_ADC_PIN PA1
|
||||
#define CURRENT_METER_ADC_PIN PA2
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
#define WS2811_GPIO GPIOA
|
||||
|
@ -200,7 +188,7 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTF (BIT(4))
|
||||
#define TARGET_IO_PORTF (BIT(4))
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17))
|
||||
|
||||
|
|
|
@ -144,15 +144,9 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_11
|
||||
|
||||
#define RSSI_ADC_GPIO_PIN PC2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
#define VBAT_ADC_PIN PC1
|
||||
#define RSSI_ADC_GPIO_PIN PC2
|
||||
#define CURRENT_METER_ADC_PIN PC3
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_13
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
|
||||
|
|
|
@ -80,33 +80,19 @@
|
|||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
|
||||
|
||||
#define M25P16_CS_GPIO GPIOB
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3,
|
||||
#define BIND_PIN PB11
|
||||
#define BIND_PIN PB11
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
/*
|
||||
|
|
|
@ -72,23 +72,11 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||
|
||||
|
||||
//#define USE_ADC
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
|
@ -98,6 +86,6 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTF (BIT(4))
|
||||
#define TARGET_IO_PORTF (BIT(4))
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
|
||||
|
|
|
@ -26,12 +26,12 @@ const uint16_t multiPWM[] = {
|
|||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
|
|
@ -88,30 +88,14 @@
|
|||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOC
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_6
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOC
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOC
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_8
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOC
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
|
||||
#define VBAT_ADC_PIN PC0
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define RSSI_ADC_PIN PC2
|
||||
#define EXTERNAL1_ADC_PIN PC3
|
||||
|
||||
#define LED_STRIP
|
||||
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
|
|
@ -119,22 +119,10 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
//#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
//#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
//#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
#define VBAT_ADC_PIN PA5
|
||||
//#define CURRENT_METER_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define LED_STRIP
|
||||
#if 1
|
||||
|
|
|
@ -33,8 +33,8 @@
|
|||
#define BARO_XCLR_PIN PC13
|
||||
#define BARO_EOC_PIN PC14
|
||||
|
||||
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_USART USART2
|
||||
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_USART USART2
|
||||
|
||||
#define USE_EXTI
|
||||
|
||||
|
@ -147,26 +147,14 @@
|
|||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOB
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_4
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOA
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOA
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define RSSI_ADC_PIN PA1
|
||||
#define EXTERNAL1_ADC_PIN PA5
|
||||
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
|
||||
|
||||
|
|
|
@ -83,22 +83,10 @@
|
|||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOB
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_4
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOA
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOA
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define RSSI_ADC_PIN PA1
|
||||
#define EXTERNAL1_ADC_PIN PA5
|
||||
|
||||
//#define LED_STRIP
|
||||
//#define LED_STRIP_TIMER TIM3
|
||||
|
|
|
@ -159,26 +159,14 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define CURRENT_METER_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
|
@ -210,6 +198,7 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
||||
|
||||
#define BUTTONS
|
||||
#define BUTTON_A_PORT GPIOB
|
||||
|
|
|
@ -87,26 +87,14 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||
|
||||
#define ADC_INSTANCE ADC2
|
||||
#define ADC_DMA_CHANNEL DMA2_Channel1
|
||||
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOA
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_2
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_12
|
||||
#define CURRENT_METER_ADC_PIN PA2
|
||||
#define VBAT_ADC_PIN PA5
|
||||
#define RSSI_ADC_PIN PB2
|
||||
|
||||
#define LED_STRIP
|
||||
#if 1
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
|
||||
#define WS2811_GPIO GPIOB
|
||||
|
|
|
@ -38,22 +38,17 @@
|
|||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define PORT103R_SPI_INSTANCE SPI2
|
||||
#define PORT103R_SPI_CS_GPIO GPIOB
|
||||
#define PORT103R_SPI_CS_PIN PB12
|
||||
|
||||
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
|
||||
#define M25P16_CS_GPIO PORT103R_SPI_CS_GPIO
|
||||
#define M25P16_CS_PIN PORT103R_SPI_CS_PIN
|
||||
#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE
|
||||
|
||||
#define MPU6000_CS_GPIO PORT103R_SPI_CS_GPIO
|
||||
#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN
|
||||
#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE
|
||||
|
||||
#define MPU6500_CS_GPIO PORT103R_SPI_CS_GPIO
|
||||
#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN
|
||||
#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
|
||||
#define GYRO
|
||||
#define USE_FAKE_GYRO
|
||||
|
@ -115,22 +110,10 @@
|
|||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define USE_ADC
|
||||
|
||||
#define CURRENT_METER_ADC_GPIO GPIOB
|
||||
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define VBAT_ADC_GPIO GPIOA
|
||||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_4
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOA
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
#define EXTERNAL1_ADC_GPIO GPIOA
|
||||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
#define CURRENT_METER_ADC_PIN PB1
|
||||
#define VBAT_ADC_PIN PA4
|
||||
#define RSSI_ADC_PIN PA1
|
||||
#define EXTERNAL1_ADC_PIN PA5
|
||||
|
||||
//#define LED_STRIP
|
||||
//#define LED_STRIP_TIMER TIM3
|
||||
|
|
|
@ -11,6 +11,7 @@ TARGET_SRC = \
|
|||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu3050.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer_bmp085.c \
|
||||
|
|
|
@ -20,23 +20,17 @@
|
|||
#define TARGET_BOARD_IDENTIFIER "REVO"
|
||||
|
||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||
#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
|
||||
#define CONFIG_FEATURE_RX_SERIAL
|
||||
#define CONFIG_FEATURE_ONESHOT125
|
||||
#define CONFIG_MSP_PORT 2
|
||||
#define CONFIG_RX_SERIAL_PORT 1
|
||||
|
||||
#define USBD_PRODUCT_STRING "Revolution"
|
||||
#ifdef OPBL
|
||||
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
||||
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
||||
#endif
|
||||
|
||||
#define LED0 PB5
|
||||
#define LED1 PB4
|
||||
#define BEEPER PB4
|
||||
#define INVERTER PC0 // PC0 used as inverter select GPIO
|
||||
#define INVERTER_USART USART1
|
||||
#define LED0 PB5
|
||||
#define LED1 PB4
|
||||
#define BEEPER PB4
|
||||
#define INVERTER PC0 // PC0 used as inverter select GPIO
|
||||
#define INVERTER_USART USART1
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_INSTANCE SPI1
|
||||
|
@ -110,14 +104,10 @@
|
|||
|
||||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PC1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_11
|
||||
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_12
|
||||
|
||||
#define RSSI_ADC_GPIO_PIN PA0
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_0
|
||||
#define VBAT_ADC_PIN PC2
|
||||
#define RSSI_ADC_GPIO_PIN PA0
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
//#define LED_STRIP
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue