1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 00:05:28 +03:00

SPRACINGF3EVO board support (#266)

* Initial SPRACINGF3EVO support
* General SD-Card support; enable SD-Card for EVO
This commit is contained in:
Konstantin Sharlaimov 2016-07-27 05:46:32 +03:00 committed by GitHub
parent 8817a2fb80
commit 688e75c82d
26 changed files with 1376 additions and 128 deletions

View file

@ -552,7 +552,6 @@ TARGET_SRC += $(VCP_SRC)
endif
# end target specific make file checks
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src

View file

@ -8,6 +8,7 @@ targets=("PUBLISHMETA=True" \
"TARGET=COLIBRI_RACE" \
"TARGET=EUSTM32F103RC" \
"TARGET=SPRACINGF3" \
"TARGET=SPRACINGF3EVO" \
"TARGET=LUX_RACE" \
"TARGET=MOTOLAB" \
"TARGET=NAZE" \

View file

@ -295,6 +295,7 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
typedef enum BlackboxState {
BLACKBOX_STATE_DISABLED = 0,
BLACKBOX_STATE_STOPPED,
BLACKBOX_STATE_PREPARE_LOG_FILE,
BLACKBOX_STATE_SEND_HEADER,
BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
BLACKBOX_STATE_SEND_GPS_H_HEADER,
@ -399,6 +400,7 @@ STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION
static uint32_t blackboxIteration;
static uint16_t blackboxPFrameIndex, blackboxIFrameIndex;
static uint16_t blackboxSlowFrameIterationTimer;
static bool blackboxLoggedAnyFrames;
/*
* We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
@ -418,7 +420,16 @@ static blackboxMainState_t* blackboxHistory[3];
static bool blackboxModeActivationConditionPresent = false;
static bool blackboxIsOnlyLoggingIntraframes() {
/**
* Return true if it is safe to edit the Blackbox configuration.
*/
bool blackboxMayEditConfig(void)
{
return blackboxState <= BLACKBOX_STATE_STOPPED;
}
static bool blackboxIsOnlyLoggingIntraframes()
{
return masterConfig.blackbox_rate_num == 1 && masterConfig.blackbox_rate_denom == 32;
}
@ -508,6 +519,9 @@ static void blackboxSetState(BlackboxState newState)
{
//Perform initial setup required for the new state
switch (newState) {
case BLACKBOX_STATE_PREPARE_LOG_FILE:
blackboxLoggedAnyFrames = false;
break;
case BLACKBOX_STATE_SEND_HEADER:
blackboxHeaderBudget = 0;
xmitState.headerIndex = 0;
@ -528,7 +542,6 @@ static void blackboxSetState(BlackboxState newState)
break;
case BLACKBOX_STATE_SHUTTING_DOWN:
xmitState.u.startTime = millis();
blackboxDeviceFlush();
break;
default:
;
@ -898,7 +911,19 @@ static void validateBlackboxConfig()
masterConfig.blackbox_rate_denom /= div;
}
if (masterConfig.blackbox_device >= BLACKBOX_DEVICE_END) {
// If we've chosen an unsupported device, change the device to serial
switch (masterConfig.blackbox_device) {
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
#endif
case BLACKBOX_DEVICE_SERIAL:
// Device supported, leave the setting alone
break;
default:
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
}
}
@ -945,7 +970,7 @@ void startBlackbox(void)
*/
blackboxLastArmingBeep = getArmingBeepTimeMicros();
blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
}
}
@ -954,18 +979,20 @@ void startBlackbox(void)
*/
void finishBlackbox(void)
{
if (blackboxState == BLACKBOX_STATE_RUNNING || blackboxState == BLACKBOX_STATE_PAUSED) {
switch (blackboxState) {
case BLACKBOX_STATE_DISABLED:
case BLACKBOX_STATE_STOPPED:
case BLACKBOX_STATE_SHUTTING_DOWN:
// We're already stopped/shutting down
break;
case BLACKBOX_STATE_RUNNING:
case BLACKBOX_STATE_PAUSED:
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
// Fall through
default:
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
} else if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED
&& blackboxState != BLACKBOX_STATE_SHUTTING_DOWN) {
/*
* We're shutting down in the middle of transmitting headers, so we can't log a "log completed" event.
* Just give the port back and stop immediately.
*/
blackboxDeviceClose();
blackboxSetState(BLACKBOX_STATE_STOPPED);
}
}
@ -1463,6 +1490,11 @@ void handleBlackbox(void)
}
switch (blackboxState) {
case BLACKBOX_STATE_PREPARE_LOG_FILE:
if (blackboxDeviceBeginLog()) {
blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
}
break;
case BLACKBOX_STATE_SEND_HEADER:
//On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
@ -1529,7 +1561,7 @@ void handleBlackbox(void)
* (overflowing circular buffers causes all data to be discarded, so the first few logged iterations
* could wipe out the end of the header if we weren't careful)
*/
if (blackboxDeviceFlush()) {
if (blackboxDeviceFlushForce()) {
blackboxSetState(BLACKBOX_STATE_RUNNING);
}
}
@ -1563,7 +1595,7 @@ void handleBlackbox(void)
blackboxAdvanceIterationTimers();
break;
case BLACKBOX_STATE_SHUTTING_DOWN:
//On entry of this state, startTime is set and a flush is performed
//On entry of this state, startTime is set
/*
* Wait for the log we've transmitted to make its way to the logger before we release the serial port,
@ -1571,7 +1603,7 @@ void handleBlackbox(void)
*
* Don't wait longer than it could possibly take if something funky happens.
*/
if (millis() > xmitState.u.startTime + BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS || blackboxDeviceFlush()) {
if (blackboxDeviceEndLog(blackboxLoggedAnyFrames) && (millis() > xmitState.u.startTime + BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS || blackboxDeviceFlushForce())) {
blackboxDeviceClose();
blackboxSetState(BLACKBOX_STATE_STOPPED);
}

View file

@ -25,3 +25,4 @@ void initBlackbox(void);
void handleBlackbox(void);
void startBlackbox(void);
void finishBlackbox(void);
bool blackboxMayEditConfig(void);

View file

@ -76,6 +76,7 @@
#include "config/config_master.h"
#include "io/flashfs.h"
#include "io/asyncfatfs/asyncfatfs.h"
#ifdef BLACKBOX
@ -90,6 +91,26 @@ int32_t blackboxHeaderBudget;
static serialPort_t *blackboxPort = NULL;
static portSharing_e blackboxPortSharing;
#ifdef USE_SDCARD
static struct {
afatfsFilePtr_t logFile;
afatfsFilePtr_t logDirectory;
afatfsFinder_t logDirectoryFinder;
uint32_t largestLogFileNumber;
enum {
BLACKBOX_SDCARD_INITIAL,
BLACKBOX_SDCARD_WAITING,
BLACKBOX_SDCARD_ENUMERATE_FILES,
BLACKBOX_SDCARD_CHANGE_INTO_LOG_DIRECTORY,
BLACKBOX_SDCARD_READY_TO_CREATE_LOG,
BLACKBOX_SDCARD_READY_TO_LOG
} state;
} blackboxSDCard;
#endif
void blackboxWrite(uint8_t value)
{
switch (masterConfig.blackbox_device) {
@ -97,6 +118,11 @@ void blackboxWrite(uint8_t value)
case BLACKBOX_DEVICE_FLASH:
flashfsWriteByte(value); // Write byte asynchronously
break;
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
afatfs_fputc(blackboxSDCard.logFile, value);
break;
#endif
case BLACKBOX_DEVICE_SERIAL:
default:
@ -168,6 +194,13 @@ int blackboxPrint(const char *s)
break;
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
length = strlen(s);
afatfs_fwrite(blackboxSDCard.logFile, (const uint8_t*) s, length); // Ignore failures due to buffers filling up
break;
#endif
case BLACKBOX_DEVICE_SERIAL:
default:
pos = (uint8_t*) s;
@ -228,7 +261,8 @@ void blackboxWriteS16(int16_t value)
/**
* Write a 2 bit tag followed by 3 signed fields of 2, 4, 6 or 32 bits
*/
void blackboxWriteTag2_3S32(int32_t *values) {
void blackboxWriteTag2_3S32(int32_t *values)
{
static const int NUM_FIELDS = 3;
//Need to be enums rather than const ints if we want to switch on them (due to being C)
@ -352,7 +386,8 @@ void blackboxWriteTag2_3S32(int32_t *values) {
/**
* Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits.
*/
void blackboxWriteTag8_4S16(int32_t *values) {
void blackboxWriteTag8_4S16(int32_t *values)
{
//Need to be enums rather than const ints if we want to switch on them (due to being C)
enum {
@ -490,13 +525,36 @@ void blackboxWriteFloat(float value)
/**
* If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now.
*
* Returns true if all data has been flushed to the device.
* Intended to be called regularly for the blackbox device to perform housekeeping.
*/
bool blackboxDeviceFlush(void)
void blackboxDeviceFlush(void)
{
switch (masterConfig.blackbox_device) {
#ifdef USE_FLASHFS
/*
* This is our only output device which requires us to call flush() in order for it to write anything. The other
* devices will progressively write in the background without Blackbox calling anything.
*/
case BLACKBOX_DEVICE_FLASH:
flashfsFlushAsync();
break;
#endif
default:
;
}
}
/**
* If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now.
*
* Returns true if all data has been written to the device.
*/
bool blackboxDeviceFlushForce(void)
{
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
//Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer
// Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer
return isSerialTransmitBufferEmpty(blackboxPort);
#ifdef USE_FLASHFS
@ -504,6 +562,14 @@ bool blackboxDeviceFlush(void)
return flashfsFlushAsync();
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
/* SD card will flush itself without us calling it, but we need to call flush manually in order to check
* if it's done yet or not!
*/
return afatfs_flush();
#endif
default:
return false;
}
@ -567,6 +633,17 @@ bool blackboxDeviceOpen(void)
return true;
break;
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
if (afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_FATAL || afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_UNKNOWN || afatfs_isFull()) {
return false;
}
blackboxMaxHeaderBytesPerIteration = BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION;
return true;
break;
#endif
default:
return false;
}
@ -579,6 +656,7 @@ void blackboxDeviceClose(void)
{
switch (masterConfig.blackbox_device) {
case BLACKBOX_DEVICE_SERIAL:
// Since the serial port could be shared with other processes, we have to give it back here
closeSerialPort(blackboxPort);
blackboxPort = NULL;
@ -590,11 +668,189 @@ void blackboxDeviceClose(void)
mspAllocateSerialPorts();
}
break;
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
// No-op since the flash doesn't have a "close" and there's nobody else to hand control of it to.
default:
;
}
}
#ifdef USE_SDCARD
static void blackboxLogDirCreated(afatfsFilePtr_t directory)
{
if (directory) {
blackboxSDCard.logDirectory = directory;
afatfs_findFirst(blackboxSDCard.logDirectory, &blackboxSDCard.logDirectoryFinder);
blackboxSDCard.state = BLACKBOX_SDCARD_ENUMERATE_FILES;
} else {
// Retry
blackboxSDCard.state = BLACKBOX_SDCARD_INITIAL;
}
}
static void blackboxLogFileCreated(afatfsFilePtr_t file)
{
if (file) {
blackboxSDCard.logFile = file;
blackboxSDCard.largestLogFileNumber++;
blackboxSDCard.state = BLACKBOX_SDCARD_READY_TO_LOG;
} else {
// Retry
blackboxSDCard.state = BLACKBOX_SDCARD_READY_TO_CREATE_LOG;
}
}
static void blackboxCreateLogFile()
{
uint32_t remainder = blackboxSDCard.largestLogFileNumber + 1;
char filename[13];
filename[0] = 'L';
filename[1] = 'O';
filename[2] = 'G';
for (int i = 7; i >= 3; i--) {
filename[i] = (remainder % 10) + '0';
remainder /= 10;
}
filename[8] = '.';
filename[9] = 'T';
filename[10] = 'X';
filename[11] = 'T';
filename[12] = 0;
blackboxSDCard.state = BLACKBOX_SDCARD_WAITING;
afatfs_fopen(filename, "as", blackboxLogFileCreated);
}
/**
* Begin a new log on the SDCard.
*
* Keep calling until the function returns true (open is complete).
*/
static bool blackboxSDCardBeginLog()
{
fatDirectoryEntry_t *directoryEntry;
doMore:
switch (blackboxSDCard.state) {
case BLACKBOX_SDCARD_INITIAL:
if (afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_READY) {
blackboxSDCard.state = BLACKBOX_SDCARD_WAITING;
afatfs_mkdir("logs", blackboxLogDirCreated);
}
break;
case BLACKBOX_SDCARD_WAITING:
// Waiting for directory entry to be created
break;
case BLACKBOX_SDCARD_ENUMERATE_FILES:
while (afatfs_findNext(blackboxSDCard.logDirectory, &blackboxSDCard.logDirectoryFinder, &directoryEntry) == AFATFS_OPERATION_SUCCESS) {
if (directoryEntry && !fat_isDirectoryEntryTerminator(directoryEntry)) {
// If this is a log file, parse the log number from the filename
if (
directoryEntry->filename[0] == 'L' && directoryEntry->filename[1] == 'O' && directoryEntry->filename[2] == 'G'
&& directoryEntry->filename[8] == 'T' && directoryEntry->filename[9] == 'X' && directoryEntry->filename[10] == 'T'
) {
char logSequenceNumberString[6];
memcpy(logSequenceNumberString, directoryEntry->filename + 3, 5);
logSequenceNumberString[5] = '\0';
blackboxSDCard.largestLogFileNumber = MAX((uint32_t) atoi(logSequenceNumberString), blackboxSDCard.largestLogFileNumber);
}
} else {
// We're done checking all the files on the card, now we can create a new log file
afatfs_findLast(blackboxSDCard.logDirectory);
blackboxSDCard.state = BLACKBOX_SDCARD_CHANGE_INTO_LOG_DIRECTORY;
goto doMore;
}
}
break;
case BLACKBOX_SDCARD_CHANGE_INTO_LOG_DIRECTORY:
// Change into the log directory:
if (afatfs_chdir(blackboxSDCard.logDirectory)) {
// We no longer need our open handle on the log directory
afatfs_fclose(blackboxSDCard.logDirectory, NULL);
blackboxSDCard.logDirectory = NULL;
blackboxSDCard.state = BLACKBOX_SDCARD_READY_TO_CREATE_LOG;
goto doMore;
}
break;
case BLACKBOX_SDCARD_READY_TO_CREATE_LOG:
blackboxCreateLogFile();
break;
case BLACKBOX_SDCARD_READY_TO_LOG:
return true; // Log has been created!
}
// Not finished init yet
return false;
}
#endif
/**
* Begin a new log (for devices which support separations between the logs of multiple flights).
*
* Keep calling until the function returns true (open is complete).
*/
bool blackboxDeviceBeginLog(void)
{
switch (masterConfig.blackbox_device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
return blackboxSDCardBeginLog();
#endif
default:
return true;
}
}
/**
* Terminate the current log (for devices which support separations between the logs of multiple flights).
*
* retainLog - Pass true if the log should be kept, or false if the log should be discarded (if supported).
*
* Keep calling until this returns true
*/
bool blackboxDeviceEndLog(bool retainLog)
{
#ifndef USE_SDCARD
(void) retainLog;
#endif
switch (masterConfig.blackbox_device) {
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
// Keep retrying until the close operation queues
if (
(retainLog && afatfs_fclose(blackboxSDCard.logFile, NULL))
|| (!retainLog && afatfs_funlink(blackboxSDCard.logFile, NULL))
) {
// Don't bother waiting the for the close to complete, it's queued now and will complete eventually
blackboxSDCard.logFile = NULL;
blackboxSDCard.state = BLACKBOX_SDCARD_READY_TO_CREATE_LOG;
return true;
}
return false;
#endif
default:
return true;
}
}
@ -609,6 +865,11 @@ bool isBlackboxDeviceFull(void)
return flashfsIsEOF();
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
return afatfs_isFull();
#endif
default:
return false;
}
@ -630,6 +891,11 @@ void blackboxReplenishHeaderBudget()
case BLACKBOX_DEVICE_FLASH:
freeSpace = flashfsGetWriteBufferFreeSpace();
break;
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
freeSpace = afatfs_getFreeBufferSpace();
break;
#endif
default:
freeSpace = 0;
@ -693,6 +959,12 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
#endif
#ifdef USE_SDCARD
case BLACKBOX_DEVICE_SDCARD:
// Assume that all writes will fit in the SDCard's buffers
return BLACKBOX_RESERVE_TEMPORARY_FAILURE;
#endif
default:
return BLACKBOX_RESERVE_PERMANENT_FAILURE;
}

View file

@ -26,7 +26,10 @@ typedef enum BlackboxDevice {
BLACKBOX_DEVICE_SERIAL = 0,
#ifdef USE_FLASHFS
BLACKBOX_DEVICE_FLASH,
BLACKBOX_DEVICE_FLASH = 1,
#endif
#ifdef USE_SDCARD
BLACKBOX_DEVICE_SDCARD = 2,
#endif
BLACKBOX_DEVICE_END
@ -69,10 +72,14 @@ void blackboxWriteTag8_8SVB(int32_t *values, int valueCount);
void blackboxWriteU32(int32_t value);
void blackboxWriteFloat(float value);
bool blackboxDeviceFlush(void);
void blackboxDeviceFlush(void);
bool blackboxDeviceFlushForce(void);
bool blackboxDeviceOpen(void);
void blackboxDeviceClose(void);
bool blackboxDeviceBeginLog(void);
bool blackboxDeviceEndLog(bool retainLog);
bool isBlackboxDeviceFull(void);
void blackboxReplenishHeaderBudget();

View file

@ -99,7 +99,12 @@ void mpu6500GyroInit(uint8_t lpf)
mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxCalculateDivider()); // Get Divider
// Data ready interrupt configuration
#ifdef USE_MPU9250_MAG
mpuConfiguration.write(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
#else
mpuConfiguration.write(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
#endif
#ifdef USE_MPU_DATA_READY_SIGNAL
mpuConfiguration.write(MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
#endif

View file

@ -16,6 +16,7 @@
*/
#define MPU6500_WHO_AM_I_CONST (0x70)
#define MPU9250_WHO_AM_I_CONST (0x71)
#define MPU6500_BIT_RESET (0x80)

View file

@ -26,7 +26,7 @@
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include <platform.h>
#include "common/axis.h"
#include "common/maths.h"
@ -127,8 +127,6 @@ void mpu6000SpiGyroInit(uint8_t lpf)
mpu6000AccAndGyroInit();
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
// Accel and Gyro DLPF Setting
@ -138,8 +136,7 @@ void mpu6000SpiGyroInit(uint8_t lpf)
int16_t data[3];
mpuGyroRead(data);
if ((((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) || spiGetErrorCounter(MPU6000_SPI_INSTANCE) != 0) {
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
if (((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) {
failureMode(FAILURE_GYRO_INIT_FAILED);
}
}
@ -197,7 +194,8 @@ bool mpu6000SpiDetect(void)
return false;
}
static void mpu6000AccAndGyroInit(void) {
static void mpu6000AccAndGyroInit(void)
{
if (mpuSpi6000InitDone) {
return;

View file

@ -99,16 +99,17 @@ static void mpu6500SpiInit(void)
bool mpu6500SpiDetect(void)
{
uint8_t tmp;
uint8_t sig;
mpu6500SpiInit();
mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp);
if (tmp != MPU6500_WHO_AM_I_CONST)
return false;
mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &sig);
if (sig == MPU6500_WHO_AM_I_CONST || sig == MPU9250_WHO_AM_I_CONST) {
return true;
}
return false;
}
bool mpu6500SpiAccDetect(acc_t *acc)

View file

@ -26,12 +26,6 @@
#include "bus_spi.h"
static volatile uint16_t spi1ErrorCount = 0;
static volatile uint16_t spi2ErrorCount = 0;
#ifdef STM32F303xC
static volatile uint16_t spi3ErrorCount = 0;
#endif
#ifdef USE_SPI_DEVICE_1
#ifndef SPI1_GPIO
@ -76,13 +70,34 @@ void initSpi1(void)
#endif
// Init pins
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
#ifdef USE_SDCARD_SPI1
// Configure pins and pullups for SD-card use
// No pull-up needed since we drive this pin as an output
GPIO_InitStructure.GPIO_Pin = SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
// Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
GPIO_InitStructure.GPIO_Pin = SPI1_MISO_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
// In clock-low mode, STM32 manual says we should enable a pulldown to match
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
#else
// General-purpose pin config
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
#endif
#ifdef SPI1_NSS_PIN
GPIO_InitStructure.GPIO_Pin = SPI1_NSS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
@ -101,18 +116,18 @@ void initSpi1(void)
gpio.mode = Mode_AF_PP;
gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN;
gpio.speed = Speed_50MHz;
gpioInit(GPIOA, &gpio);
gpioInit(SPI1_GPIO, &gpio);
// MISO as input
gpio.pin = SPI1_MISO_PIN;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOA, &gpio);
gpioInit(SPI1_GPIO, &gpio);
#ifdef SPI1_NSS_PIN
// NSS as gpio slave select
gpio.pin = SPI1_NSS_PIN;
gpio.mode = Mode_Out_PP;
gpioInit(GPIOA, &gpio);
gpioInit(SPI1_GPIO, &gpio);
#endif
#endif
@ -193,13 +208,35 @@ void initSpi2(void)
GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5);
#endif
GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN | SPI2_MISO_PIN | SPI2_MOSI_PIN;
// Init pins
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
#ifdef USE_SDCARD_SPI2
// Configure pins and pullups for SD-card use
// No pull-up needed since we drive this pin as an output
GPIO_InitStructure.GPIO_Pin = SPI2_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
// Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
GPIO_InitStructure.GPIO_Pin = SPI2_MISO_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
// In clock-low mode, STM32 manual says we should enable a pulldown to match
GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
#else
// General-purpose pin config
GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN | SPI2_MISO_PIN | SPI2_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
#endif
#ifdef SPI2_NSS_PIN
GPIO_InitStructure.GPIO_Pin = SPI2_NSS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
@ -288,30 +325,14 @@ bool spiInit(SPI_TypeDef *instance)
return false;
}
uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
{
if (instance == SPI1) {
spi1ErrorCount++;
} else if (instance == SPI2) {
spi2ErrorCount++;
}
#ifdef STM32F303xC
else {
spi3ErrorCount++;
return spi3ErrorCount;
}
#endif
return -1;
}
// return uint8_t value or -1 when failure
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
{
uint16_t spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET)
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
break;
}
#ifdef STM32F303xC
SPI_SendData8(instance, data);
@ -320,9 +341,10 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
SPI_I2S_SendData(instance, data);
#endif
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET)
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET){
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
break;
}
#ifdef STM32F303xC
return ((uint8_t)SPI_ReceiveData8(instance));
@ -332,7 +354,21 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
#endif
}
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
/**
* Return true if the bus is currently in the middle of a transmission.
*/
bool spiIsBusBusy(SPI_TypeDef *instance)
{
#ifdef STM32F303xC
return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
#endif
#ifdef STM32F10X
return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
#endif
}
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
{
uint16_t spiTimeout = 1000;
@ -342,7 +378,7 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
b = in ? *(in++) : 0xFF;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
break;
}
#ifdef STM32F303xC
SPI_SendData8(instance, b);
@ -351,9 +387,10 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
#ifdef STM32F10X
SPI_I2S_SendData(instance, b);
#endif
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
break;
}
#ifdef STM32F303xC
b = SPI_ReceiveData8(instance);
@ -365,8 +402,6 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
if (out)
*(out++) = b;
}
return true;
}
@ -426,23 +461,3 @@ void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
SPI_Cmd(instance, ENABLE);
}
uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
{
if (instance == SPI1) {
return spi1ErrorCount;
} else if (instance == SPI2) {
return spi2ErrorCount;
}
return 0;
}
void spiResetErrorCounter(SPI_TypeDef *instance)
{
if (instance == SPI1) {
spi1ErrorCount = 0;
} else if (instance == SPI2) {
spi2ErrorCount = 0;
}
}

View file

@ -17,6 +17,7 @@
#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
@ -24,8 +25,6 @@
bool spiInit(SPI_TypeDef *instance);
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor);
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in);
bool spiIsBusBusy(SPI_TypeDef *instance);
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len);
uint16_t spiGetErrorCounter(SPI_TypeDef *instance);
void spiResetErrorCounter(SPI_TypeDef *instance);
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len);

349
src/main/drivers/compass_ak8963.c Executable file
View file

@ -0,0 +1,349 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "build_config.h"
#include "platform.h"
#include "debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "exti.h"
#include "bus_i2c.h"
#include "bus_spi.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensor.h"
#include "compass.h"
#include "accgyro.h"
#include "accgyro_mpu.h"
#include "accgyro_mpu6500.h"
#include "accgyro_spi_mpu6500.h"
#include "compass_ak8963.h"
// This sensor is available in MPU-9250.
#ifndef AK8963_I2C_INSTANCE
#define AK8963_I2C_INSTANCE I2C_DEVICE
#endif
// AK8963, mag sensor address
#define AK8963_MAG_I2C_ADDRESS 0x0C
#define AK8963_Device_ID 0x48
// Registers
#define AK8963_MAG_REG_WHO_AM_I 0x00
#define AK8963_MAG_REG_INFO 0x01
#define AK8963_MAG_REG_STATUS1 0x02
#define AK8963_MAG_REG_HXL 0x03
#define AK8963_MAG_REG_HXH 0x04
#define AK8963_MAG_REG_HYL 0x05
#define AK8963_MAG_REG_HYH 0x06
#define AK8963_MAG_REG_HZL 0x07
#define AK8963_MAG_REG_HZH 0x08
#define AK8963_MAG_REG_STATUS2 0x09
#define AK8963_MAG_REG_CNTL 0x0a
#define AK8963_MAG_REG_ASCT 0x0c // self test
#define AK8963_MAG_REG_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value
#define AK8963_MAG_REG_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
#define AK8963_MAG_REG_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
#define READ_FLAG 0x80
#define STATUS1_DATA_READY 0x01
#define STATUS1_DATA_OVERRUN 0x02
#define STATUS2_DATA_ERROR 0x02
#define STATUS2_MAG_SENSOR_OVERFLOW 0x03
#define CNTL_MODE_POWER_DOWN 0x00
#define CNTL_MODE_ONCE 0x01
#define CNTL_MODE_CONT1 0x02
#define CNTL_MODE_CONT2 0x06
#define CNTL_MODE_SELF_TEST 0x08
#define CNTL_MODE_FUSE_ROM 0x0F
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.
#ifdef MPU6500_SPI_INSTANCE
#define MPU9250_SPI_INSTANCE
#define verifympu9250WriteRegister mpu6500WriteRegister
#define mpu9250WriteRegister mpu6500WriteRegister
#define mpu9250ReadRegister mpu6500ReadRegister
#endif
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
typedef struct queuedReadState_s {
bool waiting;
uint8_t len;
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 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(8);
__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;
}
queuedRead.len = len_;
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
queuedRead.readStartedAt = micros();
queuedRead.waiting = true;
return true;
}
static uint32_t ak8963SensorQueuedReadTimeRemaining(void)
{
if (!queuedRead.waiting) {
return 0;
}
int32_t timeSinceStarted = micros() - queuedRead.readStartedAt;
int32_t timeRemaining = 8000 - timeSinceStarted;
if (timeRemaining < 0) {
return 0;
}
return timeRemaining;
}
bool ak8963SensorCompleteRead(uint8_t *buf)
{
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining > 0) {
delayMicroseconds(timeRemaining);
}
queuedRead.waiting = false;
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer
return true;
}
#else
bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
return i2cRead(addr_, reg_, len, buf);
}
bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWrite(addr_, reg_, data);
}
#endif
bool ak8963Detect(mag_t *mag)
{
bool ack = false;
uint8_t sig = 0;
#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'
{
mag->init = ak8963Init;
mag->read = ak8963Read;
return true;
}
return false;
}
void ak8963Init()
{
bool ack;
UNUSED(ack);
uint8_t calibration[3];
uint8_t status;
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
delay(20);
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
delay(10);
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 = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
delay(10);
// Clear status registers
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
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
#else
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
#endif
}
bool ak8963Read(int16_t *magData)
{
bool ack = false;
uint8_t buf[7];
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
// 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;
bool retry = true;
restart:
switch (state) {
case CHECK_STATUS:
ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1);
state++;
return false;
case WAITING_FOR_STATUS: {
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining) {
return false;
}
ack = ak8963SensorCompleteRead(&buf[0]);
uint8_t status = buf[0];
if (!ack || ((status & STATUS1_DATA_READY) == 0 && (status & STATUS1_DATA_OVERRUN) == 0)) {
// too early. queue the status read again
state = CHECK_STATUS;
if (retry) {
retry = false;
goto restart;
}
return false;
}
// read the 6 bytes of data and the status2 register
ak8963SensorStartRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_HXL, 7);
state++;
return false;
}
case WAITING_FOR_DATA: {
uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining();
if (timeRemaining) {
return false;
}
ack = ak8963SensorCompleteRead(&buf[0]);
}
}
#else
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &buf[0]);
uint8_t status = buf[0];
if (!ack || (status & STATUS1_DATA_READY) == 0) {
return false;
}
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;
}
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];
#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
}

View file

@ -0,0 +1,22 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
bool ak8963Detect(mag_t *mag);
void ak8963Init(void);
bool ak8963Read(int16_t *magData);

View file

@ -22,7 +22,7 @@
#include "build_config.h"
#include "platform.h"
#include <platform.h>
#include "common/axis.h"
#include "common/maths.h"
@ -31,7 +31,6 @@
#include "gpio.h"
#include "bus_i2c.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensor.h"
@ -59,7 +58,7 @@
#define AK8975_MAG_REG_CNTL 0x0a
#define AK8975_MAG_REG_ASCT 0x0c // self test
bool ak8975detect(mag_t *mag)
bool ak8975Detect(mag_t *mag)
{
bool ack = false;
uint8_t sig = 0;

View file

@ -17,6 +17,6 @@
#pragma once
bool ak8975detect(mag_t *mag);
bool ak8975Detect(mag_t *mag);
void ak8975Init(void);
bool ak8975Read(int16_t *magData);

View file

@ -46,6 +46,7 @@
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/sdcard.h"
#include "drivers/buf_writer.h"
@ -57,6 +58,7 @@
#include "io/ledstrip.h"
#include "io/flashfs.h"
#include "io/beeper.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "rx/rx.h"
#include "rx/spektrum.h"
@ -159,6 +161,10 @@ static void cliFlashRead(char *cmdline);
#endif
#endif
#ifdef USE_SDCARD
static void cliSdInfo(char *cmdline);
#endif
#ifdef BEEPER
static void cliBeeper(char *cmdline);
#endif
@ -211,7 +217,7 @@ static const char * const accNames[] = { "None", "", "ADXL345", "MPU6050", "MMA8
// sync with baroSensor_e
static const char * const baroNames[] = { "", "None", "BMP085", "MS5611", "BMP280", "FAKE"};
// sync with magSensor_e
static const char * const magNames[] = { "None", "", "HMC5883", "AK8975", "MAG_GPS", "MAG_MAG3110", "FAKE"};
static const char * const magNames[] = { "None", "", "HMC5883", "AK8975", "MAG_GPS", "MAG_MAG3110", "MAG_AK8963", "FAKE"};
// sycn with rangefinderType_e
static const char * const rangefinderNames[] = { "None", "HCSR04", "SRF10"};
@ -306,6 +312,9 @@ const clicmd_t cmdTable[] = {
"\treset\r\n"
"\tload <mixer>\r\n"
"\treverse <servo> <source> r|n", cliServoMix),
#endif
#ifdef USE_SDCARD
CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
#endif
CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
#ifndef SKIP_TASK_STATISTICS
@ -365,7 +374,7 @@ static const char * const lookupTableGimbalMode[] = {
#ifdef BLACKBOX
static const char * const lookupTableBlackboxDevice[] = {
"SERIAL", "SPIFLASH"
"SERIAL", "SPIFLASH", "SDCARD"
};
#endif
@ -1637,6 +1646,77 @@ static void cliServoMix(char *cmdline)
}
#endif
#ifdef USE_SDCARD
static void cliWriteBytes(const uint8_t *buffer, int count)
{
while (count > 0) {
cliWrite(*buffer);
buffer++;
count--;
}
}
static void cliSdInfo(char *cmdline)
{
UNUSED(cmdline);
cliPrint("SD card: ");
if (!sdcard_isInserted()) {
cliPrint("None inserted\r\n");
return;
}
if (!sdcard_isInitialized()) {
cliPrint("Startup failed\r\n");
return;
}
const sdcardMetadata_t *metadata = sdcard_getMetadata();
cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
metadata->manufacturerID,
metadata->numBlocks / 2, /* One block is half a kB */
metadata->productionMonth,
metadata->productionYear,
metadata->productRevisionMajor,
metadata->productRevisionMinor
);
cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
cliPrint("'\r\n" "Filesystem: ");
switch (afatfs_getFilesystemState()) {
case AFATFS_FILESYSTEM_STATE_READY:
cliPrint("Ready");
break;
case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
cliPrint("Initializing");
break;
case AFATFS_FILESYSTEM_STATE_UNKNOWN:
case AFATFS_FILESYSTEM_STATE_FATAL:
cliPrint("Fatal");
switch (afatfs_getLastError()) {
case AFATFS_ERROR_BAD_MBR:
cliPrint(" - no FAT MBR partitions");
break;
case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
cliPrint(" - bad FAT header");
break;
case AFATFS_ERROR_GENERIC:
case AFATFS_ERROR_NONE:
; // Nothing more detailed to print
break;
}
cliPrint("\r\n");
break;
}
}
#endif
#ifdef USE_FLASHFS

View file

@ -44,6 +44,7 @@
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/sdcard.h"
#include "drivers/buf_writer.h"
#include "rx/rx.h"
@ -58,6 +59,7 @@
#include "io/ledstrip.h"
#include "io/flashfs.h"
#include "io/msp_protocol.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "telemetry/telemetry.h"
@ -84,6 +86,8 @@
#include "config/config_profile.h"
#include "config/config_master.h"
#include "blackbox/blackbox.h"
#include "version.h"
#ifdef NAZE
#include "hardware_revision.h"
@ -170,6 +174,23 @@ static const char pidnames[] =
"MAG;"
"VEL;";
typedef enum {
MSP_SDCARD_STATE_NOT_PRESENT = 0,
MSP_SDCARD_STATE_FATAL = 1,
MSP_SDCARD_STATE_CARD_INIT = 2,
MSP_SDCARD_STATE_FS_INIT = 3,
MSP_SDCARD_STATE_READY = 4,
} mspSDCardState_e;
typedef enum {
MSP_SDCARD_FLAG_SUPPORTTED = 1,
} mspSDCardFlags_e;
typedef enum {
MSP_FLASHFS_BIT_READY = 1,
MSP_FLASHFS_BIT_SUPPORTED = 2,
} mspFlashfsFlags_e;
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
static mspPort_t *currentPort;
@ -314,6 +335,55 @@ reset:
}
}
static void serializeSDCardSummaryReply(void)
{
headSerialReply(3 + 2 * 4);
#ifdef USE_SDCARD
uint8_t flags = MSP_SDCARD_FLAG_SUPPORTTED;
uint8_t state;
serialize8(flags);
// Merge the card and filesystem states together
if (!sdcard_isInserted()) {
state = MSP_SDCARD_STATE_NOT_PRESENT;
} else if (!sdcard_isFunctional()) {
state = MSP_SDCARD_STATE_FATAL;
} else {
switch (afatfs_getFilesystemState()) {
case AFATFS_FILESYSTEM_STATE_READY:
state = MSP_SDCARD_STATE_READY;
break;
case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
if (sdcard_isInitialized()) {
state = MSP_SDCARD_STATE_FS_INIT;
} else {
state = MSP_SDCARD_STATE_CARD_INIT;
}
break;
case AFATFS_FILESYSTEM_STATE_FATAL:
case AFATFS_FILESYSTEM_STATE_UNKNOWN:
default:
state = MSP_SDCARD_STATE_FATAL;
break;
}
}
serialize8(state);
serialize8(afatfs_getLastError());
// Write free space and total space in kilobytes
serialize32(afatfs_getContiguousFreeSpace() / 1024);
serialize32(sdcard_getMetadata()->numBlocks / 2); // Block size is half a kilobyte
#else
serialize8(0);
serialize8(0);
serialize8(0);
serialize32(0);
serialize32(0);
#endif
}
static void serializeDataflashSummaryReply(void)
{
headSerialReply(1 + 3 * 4);
@ -1100,6 +1170,25 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
#endif
case MSP_BLACKBOX_CONFIG:
headSerialReply(4);
#ifdef BLACKBOX
serialize8(1); //Blackbox supported
serialize8(masterConfig.blackbox_device);
serialize8(masterConfig.blackbox_rate_num);
serialize8(masterConfig.blackbox_rate_denom);
#else
serialize8(0); // Blackbox not supported
serialize8(0);
serialize8(0);
serialize8(0);
#endif
break;
case MSP_SDCARD_SUMMARY:
serializeSDCardSummaryReply();
break;
case MSP_BF_BUILD_INFO:
headSerialReply(11 + 4 + 4);
for (i = 0; i < 11; i++)
@ -1397,6 +1486,17 @@ static bool processInCommand(void)
readEEPROM();
break;
#ifdef BLACKBOX
case MSP_SET_BLACKBOX_CONFIG:
// Don't allow config to be updated while Blackbox is logging
if (!blackboxMayEditConfig())
return false;
masterConfig.blackbox_device = read8();
masterConfig.blackbox_rate_num = read8();
masterConfig.blackbox_rate_denom = read8();
break;
#endif
#ifdef USE_FLASHFS
case MSP_DATAFLASH_ERASE:
flashfsEraseCompletely();

View file

@ -47,6 +47,7 @@
#include "drivers/inverter.h"
#include "drivers/flash_m25p16.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/sdcard.h"
#include "drivers/gyro_sync.h"
#include "rx/rx.h"
@ -60,6 +61,7 @@
#include "io/gimbal.h"
#include "io/ledstrip.h"
#include "io/display.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "scheduler/scheduler.h"
@ -493,6 +495,27 @@ void init(void)
flashfsInit();
#endif
#ifdef USE_SDCARD
bool sdcardUseDMA = false;
sdcardInsertionDetectInit();
#ifdef SDCARD_DMA_CHANNEL_TX
#if defined(LED_STRIP) && defined(WS2811_DMA_CHANNEL)
// Ensure the SPI Tx DMA doesn't overlap with the led strip
sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_CHANNEL;
#else
sdcardUseDMA = true;
#endif
#endif
sdcard_init(sdcardUseDMA);
afatfs_init();
#endif
#ifdef BLACKBOX
initBlackbox();
#endif
@ -569,6 +592,10 @@ int main(void)
#endif
#ifdef MAG
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
#if defined(MPU6500_SPI_INSTANCE) && defined(USE_MAG_AK8963)
// fixme temporary solution for AK6983 via slave I2C on MPU9250
rescheduleTask(TASK_COMPASS, 1000000 / 40);
#endif
#endif
#ifdef BARO
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));

View file

@ -65,6 +65,7 @@
#include "io/serial_cli.h"
#include "io/serial_msp.h"
#include "io/statusindicator.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "rx/rx.h"
#include "rx/msp.h"
@ -612,6 +613,10 @@ void taskMainPidLoop(void)
writeMotors();
}
#ifdef USE_SDCARD
afatfs_poll();
#endif
#ifdef BLACKBOX
if (!cliMode && feature(FEATURE_BLACKBOX)) {
handleBlackbox();

View file

@ -25,7 +25,8 @@ typedef enum {
MAG_AK8975 = 3,
MAG_GPS = 4,
MAG_MAG3110 = 5,
MAG_FAKE = 6,
MAG_AK8963 = 6,
MAG_FAKE = 7,
} magSensor_e;
#define MAG_MAX MAG_FAKE

View file

@ -55,6 +55,7 @@
#include "drivers/compass.h"
#include "drivers/compass_hmc5883l.h"
#include "drivers/compass_ak8975.h"
#include "drivers/compass_ak8963.h"
#include "drivers/compass_mag3110.h"
#include "drivers/sonar_hcsr04.h"
@ -119,7 +120,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
}
#endif
#if defined(SPRACINGF3)
#if defined(SPRACINGF3) || defined(SPRACINGF3EVO)
static const extiConfig_t spRacingF3MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPort = GPIOC,
@ -353,17 +354,21 @@ bool detectGyro(void)
case GYRO_MPU6500:
#ifdef USE_GYRO_MPU6500
#ifdef USE_GYRO_SPI_MPU6500
if (mpu6500GyroDetect(&gyro) || mpu6500SpiGyroDetect(&gyro))
#else
if (mpu6500GyroDetect(&gyro))
#endif
{
if (mpu6500GyroDetect(&gyro)) {
gyroHardware = GYRO_MPU6500;
#ifdef GYRO_MPU6500_ALIGN
gyroAlign = GYRO_MPU6500_ALIGN;
#endif
break;
}
#endif
#ifdef USE_GYRO_SPI_MPU6500
if (mpu6500SpiGyroDetect(&gyro)) {
gyroHardware = GYRO_MPU6500;
#ifdef GYRO_MPU6500_ALIGN
gyroAlign = GYRO_MPU6500_ALIGN;
#endif
break;
}
#endif
@ -484,12 +489,17 @@ retry:
; // fallthrough
case ACC_MPU6500:
#ifdef USE_ACC_MPU6500
#ifdef USE_ACC_SPI_MPU6500
if (mpu6500AccDetect(&acc) || mpu6500SpiAccDetect(&acc))
#else
if (mpu6500AccDetect(&acc))
if (mpu6500AccDetect(&acc)) {
#ifdef ACC_MPU6500_ALIGN
accAlign = ACC_MPU6500_ALIGN;
#endif
{
accHardware = ACC_MPU6500;
break;
}
#endif
#ifdef USE_ACC_SPI_MPU6500
if (mpu6500SpiAccDetect(&acc)) {
#ifdef ACC_MPU6500_ALIGN
accAlign = ACC_MPU6500_ALIGN;
#endif
@ -498,6 +508,7 @@ retry:
}
#endif
; // fallthrough
case ACC_FAKE:
#ifdef USE_FAKE_ACC
if (fakeAccDetect(&acc)) {
@ -682,7 +693,7 @@ static void detectMag(magSensor_e magHardwareToUse)
case MAG_AK8975:
#ifdef USE_MAG_AK8975
if (ak8975detect(&mag)) {
if (ak8975Detect(&mag)) {
#ifdef MAG_AK8975_ALIGN
magAlign = MAG_AK8975_ALIGN;
#endif
@ -692,6 +703,18 @@ static void detectMag(magSensor_e magHardwareToUse)
#endif
; // fallthrough
case MAG_AK8963:
#ifdef USE_MAG_AK8963
if (ak8963Detect(&mag)) {
#ifdef MAG_AK8963_ALIGN
magAlign = MAG_AK8963_ALIGN;
#endif
magHardware = MAG_AK8963;
break;
}
#endif
; // fallthrough
case MAG_GPS:
#ifdef GPS
if (gpsMagDetect(&mag)) {

View file

@ -65,6 +65,7 @@
#define USE_BARO_MS5611
#define MAG
#define USE_MPU9250_MAG // Bypass enable
#define USE_MAG_HMC5883
#define USE_MAG_AK8975

View file

@ -0,0 +1,86 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM / UART2 RX
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PPM
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9}, // PWM3
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9}, // PWM4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM8
// UART3 RX/TX
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
// IR / LED Strip Pad
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP
};

View file

@ -0,0 +1,211 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "SPEV"
#define LED0 PB8
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
#define USE_GYRO_SPI_MPU6500
#define ACC
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
#define BARO
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8963
//#define USE_MAG_MAG3110 // External
//#define USE_MAG_HMC5883 // External
#define MAG_AK8963_ALIGN CW90_DEG_FLIP
//#define SONAR
#define USB_IO
#define USE_VCP
#define USE_USART1
#define USE_USART2
#define USE_USART3
#define SERIAL_PORT_COUNT 4
#ifndef UART1_GPIO
#define UART1_TX_PIN GPIO_Pin_9 // PA9
#define UART1_RX_PIN GPIO_Pin_10 // PA10
#define UART1_GPIO GPIOA
#define UART1_GPIO_AF GPIO_AF_7
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
#endif
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
#define UART2_RX_PIN GPIO_Pin_15 // PA15
#define UART2_GPIO GPIOA
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource14
#define UART2_RX_PINSOURCE GPIO_PinSource15
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#endif
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_SPI
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard)
#define SPI1_GPIO GPIOB
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI1_NSS_PIN Pin_9
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource9
#define SPI1_SCK_PIN Pin_3
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
#define SPI1_MISO_PIN Pin_4
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
#define SPI1_MOSI_PIN Pin_5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_SCK_PIN Pin_13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
#define SPI2_MISO_PIN Pin_14
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
#define SPI2_MOSI_PIN Pin_15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN GPIO_Pin_14
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
#define SDCARD_DETECT_GPIO_PORT GPIOC
#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
#define MPU6500_CS_GPIO_CLK_PERIPHERAL SPI1_GPIO_PERIPHERAL
#define MPU6500_CS_GPIO SPI1_GPIO
#define MPU6500_CS_PIN GPIO_Pin_9
#define MPU6500_SPI_INSTANCE SPI1
#define USE_ADC
#define ADC_INSTANCE ADC2
#define VBAT_ADC_PIN PA4
#define CURRENT_METER_ADC_PIN PA5
#define RSSI_ADC_PIN PB2
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_6
#define WS2811_PIN GPIO_Pin_8
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM1
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
/*
#define TRANSPONDER
#define TRANSPONDER_GPIO GPIOA
#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define TRANSPONDER_GPIO_AF GPIO_AF_6
#define TRANSPONDER_PIN GPIO_Pin_8
#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8
#define TRANSPONDER_TIMER TIM1
#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2
#define TRANSPONDER_IRQ DMA1_Channel2_IRQn
#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
*/
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SPEKTRUM_BIND // USART3
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define NAV
#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))

View file

@ -0,0 +1,13 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_ms5611.c \
drivers/barometer_bmp280.c \
drivers/compass_mag3110.c \
drivers/compass_ak8963.c \
drivers/compass_hmc5883l.c