mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Initial rework - removing target specific code from main.c
Moved FLASH to masterConfig Moved LED (named statusLeds) to masterConfig Fixed up some targets to remove defines from main.c
This commit is contained in:
parent
3a634ae5c5
commit
f7518203aa
21 changed files with 288 additions and 165 deletions
|
@ -31,6 +31,8 @@
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
#include "drivers/vcd.h"
|
#include "drivers/vcd.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/flash.h"
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
|
@ -90,10 +92,12 @@
|
||||||
#define beeperConfig(x) (&masterConfig.beeperConfig)
|
#define beeperConfig(x) (&masterConfig.beeperConfig)
|
||||||
#define sonarConfig(x) (&masterConfig.sonarConfig)
|
#define sonarConfig(x) (&masterConfig.sonarConfig)
|
||||||
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
|
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
|
||||||
|
#define statusLedConfig(x) (&masterConfig.statusLedConfig)
|
||||||
#define osdProfile(x) (&masterConfig.osdProfile)
|
#define osdProfile(x) (&masterConfig.osdProfile)
|
||||||
#define vcdProfile(x) (&masterConfig.vcdProfile)
|
#define vcdProfile(x) (&masterConfig.vcdProfile)
|
||||||
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
|
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
|
||||||
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
|
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
|
||||||
|
#define flashConfig(x) (&masterConfig.flashConfig)
|
||||||
|
|
||||||
|
|
||||||
// System-wide
|
// System-wide
|
||||||
|
@ -162,6 +166,8 @@ typedef struct master_s {
|
||||||
serialConfig_t serialConfig;
|
serialConfig_t serialConfig;
|
||||||
telemetryConfig_t telemetryConfig;
|
telemetryConfig_t telemetryConfig;
|
||||||
|
|
||||||
|
statusLedConfig_t statusLedConfig;
|
||||||
|
|
||||||
#ifdef USE_PPM
|
#ifdef USE_PPM
|
||||||
ppmConfig_t ppmConfig;
|
ppmConfig_t ppmConfig;
|
||||||
#endif
|
#endif
|
||||||
|
@ -226,6 +232,10 @@ typedef struct master_s {
|
||||||
blackboxConfig_t blackboxConfig;
|
blackboxConfig_t blackboxConfig;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
flashConfig_t flashConfig;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint32_t beeper_off_flags;
|
uint32_t beeper_off_flags;
|
||||||
uint32_t preferred_beeper_off_flags;
|
uint32_t preferred_beeper_off_flags;
|
||||||
|
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include "drivers/io_types.h"
|
||||||
|
|
||||||
typedef struct flashGeometry_s {
|
typedef struct flashGeometry_s {
|
||||||
uint16_t sectors; // Count of the number of erasable blocks on the device
|
uint16_t sectors; // Count of the number of erasable blocks on the device
|
||||||
|
@ -29,3 +30,7 @@ typedef struct flashGeometry_s {
|
||||||
|
|
||||||
uint32_t totalSize; // This is just sectorSize * sectors
|
uint32_t totalSize; // This is just sectorSize * sectors
|
||||||
} flashGeometry_t;
|
} flashGeometry_t;
|
||||||
|
|
||||||
|
typedef struct flashConfig_s {
|
||||||
|
ioTag_t csTag;
|
||||||
|
} flashConfig_t;
|
||||||
|
|
|
@ -208,27 +208,21 @@ static bool m25p16_readIdentification()
|
||||||
* Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with
|
* Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with
|
||||||
* m25p16_getGeometry().
|
* m25p16_getGeometry().
|
||||||
*/
|
*/
|
||||||
bool m25p16_init(ioTag_t csTag)
|
bool m25p16_init(flashConfig_t *flashConfig)
|
||||||
{
|
{
|
||||||
/*
|
/*
|
||||||
if we have already detected a flash device we can simply exit
|
if we have already detected a flash device we can simply exit
|
||||||
|
|
||||||
TODO: change the init param in favour of flash CFG when ParamGroups work is done
|
|
||||||
then cs pin can be specified in hardware_revision.c or config.c (dependent on revision).
|
|
||||||
*/
|
*/
|
||||||
if (geometry.sectors) {
|
if (geometry.sectors) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (csTag) {
|
if (flashConfig->csTag) {
|
||||||
m25p16CsPin = IOGetByTag(csTag);
|
m25p16CsPin = IOGetByTag(flashConfig->csTag);
|
||||||
} else {
|
} else {
|
||||||
#ifdef M25P16_CS_PIN
|
|
||||||
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
|
|
||||||
#else
|
|
||||||
return false;
|
return false;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
IOInit(m25p16CsPin, OWNER_FLASH_CS, 0);
|
IOInit(m25p16CsPin, OWNER_FLASH_CS, 0);
|
||||||
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
|
|
|
@ -18,11 +18,11 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "io_types.h"
|
#include "flash.h"
|
||||||
|
|
||||||
#define M25P16_PAGESIZE 256
|
#define M25P16_PAGESIZE 256
|
||||||
|
|
||||||
bool m25p16_init(ioTag_t csTag);
|
bool m25p16_init(flashConfig_t *flashConfig);
|
||||||
|
|
||||||
void m25p16_eraseSector(uint32_t address);
|
void m25p16_eraseSector(uint32_t address);
|
||||||
void m25p16_eraseCompletely();
|
void m25p16_eraseCompletely();
|
||||||
|
|
|
@ -22,82 +22,23 @@
|
||||||
|
|
||||||
#include "light_led.h"
|
#include "light_led.h"
|
||||||
|
|
||||||
static const IO_t leds[] = {
|
static IO_t leds[LED_NUMBER];
|
||||||
#ifdef LED0
|
static uint8_t ledPolarity = 0;
|
||||||
DEFIO_IO(LED0),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED1
|
|
||||||
DEFIO_IO(LED1),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED2
|
|
||||||
DEFIO_IO(LED2),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
|
||||||
#ifdef LED0_A
|
|
||||||
DEFIO_IO(LED0_A),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_A
|
|
||||||
DEFIO_IO(LED1_A),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_A
|
|
||||||
DEFIO_IO(LED2_A),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
uint8_t ledPolarity = 0
|
void ledInit(statusLedConfig_t *statusLedConfig)
|
||||||
#ifdef LED0_INVERTED
|
|
||||||
| BIT(0)
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_INVERTED
|
|
||||||
| BIT(1)
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_INVERTED
|
|
||||||
| BIT(2)
|
|
||||||
#endif
|
|
||||||
#ifdef LED0_A_INVERTED
|
|
||||||
| BIT(3)
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_A_INVERTED
|
|
||||||
| BIT(4)
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_A_INVERTED
|
|
||||||
| BIT(5)
|
|
||||||
#endif
|
|
||||||
;
|
|
||||||
|
|
||||||
static uint8_t ledOffset = 0;
|
|
||||||
|
|
||||||
void ledInit(bool alternative_led)
|
|
||||||
{
|
{
|
||||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
|
||||||
if (alternative_led) {
|
|
||||||
ledOffset = LED_NUMBER;
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
UNUSED(alternative_led);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
LED2_OFF;
|
LED2_OFF;
|
||||||
|
|
||||||
|
ledPolarity = statusLedConfig->polarity;
|
||||||
for (int i = 0; i < LED_NUMBER; i++) {
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
if (leds[i + ledOffset]) {
|
if (statusLedConfig->ledTags[i]) {
|
||||||
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_INDEX(i));
|
leds[i] = IOGetByTag(statusLedConfig->ledTags[i]);
|
||||||
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
|
||||||
|
IOConfigGPIO(leds[i], IOCFG_OUT_PP);
|
||||||
|
} else {
|
||||||
|
leds[i] = IO_NONE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -108,11 +49,11 @@ void ledInit(bool alternative_led)
|
||||||
|
|
||||||
void ledToggle(int led)
|
void ledToggle(int led)
|
||||||
{
|
{
|
||||||
IOToggle(leds[led + ledOffset]);
|
IOToggle(leds[led]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ledSet(int led, bool on)
|
void ledSet(int led, bool on)
|
||||||
{
|
{
|
||||||
const bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
const bool inverted = (1 << (led)) & ledPolarity;
|
||||||
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
IOWrite(leds[led], on ? inverted : !inverted);
|
||||||
}
|
}
|
||||||
|
|
|
@ -17,8 +17,15 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/io_types.h"
|
||||||
|
|
||||||
#define LED_NUMBER 3
|
#define LED_NUMBER 3
|
||||||
|
|
||||||
|
typedef struct statusLedConfig_s {
|
||||||
|
ioTag_t ledTags[LED_NUMBER];
|
||||||
|
uint8_t polarity;
|
||||||
|
} statusLedConfig_t;
|
||||||
|
|
||||||
// Helpful macros
|
// Helpful macros
|
||||||
#ifdef LED0
|
#ifdef LED0
|
||||||
# define LED0_TOGGLE ledToggle(0)
|
# define LED0_TOGGLE ledToggle(0)
|
||||||
|
@ -50,6 +57,6 @@
|
||||||
# define LED2_ON do {} while(0)
|
# define LED2_ON do {} while(0)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void ledInit(bool alternative_led);
|
void ledInit(statusLedConfig_t *statusLedConfig);
|
||||||
void ledToggle(int led);
|
void ledToggle(int led);
|
||||||
void ledSet(int led, bool state);
|
void ledSet(int led, bool state);
|
||||||
|
|
|
@ -490,6 +490,46 @@ void resetMax7456Config(vcdProfile_t *pVcdProfile)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
void resetStatusLedConfig(statusLedConfig_t *statusLedConfig)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
|
statusLedConfig->ledTags[i] = IO_TAG_NONE;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef LED0
|
||||||
|
statusLedConfig->ledTags[0] = IO_TAG(LED0);
|
||||||
|
#endif
|
||||||
|
#ifdef LED1
|
||||||
|
statusLedConfig->ledTags[1] = IO_TAG(LED1);
|
||||||
|
#endif
|
||||||
|
#ifdef LED2
|
||||||
|
statusLedConfig->ledTags[2] = IO_TAG(LED2);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
statusLedConfig->polarity = 0
|
||||||
|
#ifdef LED0_INVERTED
|
||||||
|
| BIT(0)
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_INVERTED
|
||||||
|
| BIT(1)
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_INVERTED
|
||||||
|
| BIT(2)
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
void resetFlashConfig(flashConfig_t *flashConfig)
|
||||||
|
{
|
||||||
|
#ifdef M25P16_CS_PIN
|
||||||
|
flashConfig->csTag = IO_TAG(M25P16_CS_PIN);
|
||||||
|
#else
|
||||||
|
flashConfig->csTag = IO_TAG_NONE;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t getCurrentProfile(void)
|
uint8_t getCurrentProfile(void)
|
||||||
{
|
{
|
||||||
return masterConfig.current_profile_index;
|
return masterConfig.current_profile_index;
|
||||||
|
@ -789,6 +829,12 @@ void createDefaultConfig(master_t *config)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
resetFlashConfig(&config->flashConfig);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
resetStatusLedConfig(&config->statusLedConfig);
|
||||||
|
|
||||||
#if defined(TARGET_CONFIG)
|
#if defined(TARGET_CONFIG)
|
||||||
targetConfiguration(config);
|
targetConfiguration(config);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -124,6 +124,10 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#ifdef TARGET_BUS_INIT
|
||||||
|
void targetBusInit(void);
|
||||||
|
#endif
|
||||||
|
|
||||||
extern uint8_t motorControlEnable;
|
extern uint8_t motorControlEnable;
|
||||||
|
|
||||||
#ifdef SOFTSERIAL_LOOPBACK
|
#ifdef SOFTSERIAL_LOOPBACK
|
||||||
|
@ -172,11 +176,7 @@ void init(void)
|
||||||
// Latch active features to be used for feature() in the remainder of init().
|
// Latch active features to be used for feature() in the remainder of init().
|
||||||
latchActiveFeatures();
|
latchActiveFeatures();
|
||||||
|
|
||||||
#ifdef ALIENFLIGHTF3
|
ledInit(&masterConfig.statusLedConfig);
|
||||||
ledInit(hardwareRevision == AFF3_REV_1 ? false : true);
|
|
||||||
#else
|
|
||||||
ledInit(false);
|
|
||||||
#endif
|
|
||||||
LED2_ON;
|
LED2_ON;
|
||||||
|
|
||||||
#ifdef USE_EXTI
|
#ifdef USE_EXTI
|
||||||
|
@ -291,7 +291,6 @@ void init(void)
|
||||||
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
|
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef BEEPER
|
||||||
|
@ -306,6 +305,9 @@ void init(void)
|
||||||
bstInit(BST_DEVICE);
|
bstInit(BST_DEVICE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef TARGET_BUS_INIT
|
||||||
|
targetBusInit();
|
||||||
|
#else
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
#ifdef USE_SPI_DEVICE_1
|
#ifdef USE_SPI_DEVICE_1
|
||||||
spiInit(SPIDEV_1);
|
spiInit(SPIDEV_1);
|
||||||
|
@ -314,66 +316,37 @@ void init(void)
|
||||||
spiInit(SPIDEV_2);
|
spiInit(SPIDEV_2);
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_SPI_DEVICE_3
|
#ifdef USE_SPI_DEVICE_3
|
||||||
#ifdef ALIENFLIGHTF3
|
|
||||||
if (hardwareRevision == AFF3_REV_2) {
|
|
||||||
spiInit(SPIDEV_3);
|
spiInit(SPIDEV_3);
|
||||||
}
|
|
||||||
#else
|
|
||||||
spiInit(SPIDEV_3);
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_SPI_DEVICE_4
|
#ifdef USE_SPI_DEVICE_4
|
||||||
spiInit(SPIDEV_4);
|
spiInit(SPIDEV_4);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef VTX
|
#ifdef USE_I2C
|
||||||
vtxInit();
|
i2cInit(I2C_DEVICE);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||||
updateHardwareRevision();
|
updateHardwareRevision();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(NAZE)
|
#ifdef VTX
|
||||||
if (hardwareRevision == NAZE32_SP) {
|
vtxInit();
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
|
||||||
} else {
|
|
||||||
serialRemovePort(SERIAL_PORT_USART3);
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SPRACINGF3) && defined(SONAR) && defined(USE_SOFTSERIAL2)
|
#if defined(SONAR_SOFTSERIAL2_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL2)
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SPRACINGF3MINI) || defined(OMNIBUS) || defined(X_RACERSPI)
|
#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL1)
|
||||||
#if defined(SONAR) && defined(USE_SOFTSERIAL1)
|
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_I2C
|
|
||||||
#if defined(NAZE)
|
|
||||||
if (hardwareRevision != NAZE32_SP) {
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
} else {
|
|
||||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#elif defined(CC3D)
|
|
||||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_ADC
|
#ifdef USE_ADC
|
||||||
/* these can be removed from features! */
|
/* these can be removed from features! */
|
||||||
|
@ -383,7 +356,6 @@ void init(void)
|
||||||
adcInit(&masterConfig.adcConfig);
|
adcInit(&masterConfig.adcConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
initBoardAlignment(&masterConfig.boardAlignment);
|
initBoardAlignment(&masterConfig.boardAlignment);
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef CMS
|
||||||
|
@ -513,12 +485,8 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
#ifdef NAZE
|
#if defined(USE_FLASH_M25P16)
|
||||||
if (hardwareRevision == NAZE32_REV5) {
|
m25p16_init(&masterConfig.flashConfig);
|
||||||
m25p16_init(IO_TAG_NONE);
|
|
||||||
}
|
|
||||||
#elif defined(USE_FLASH_M25P16)
|
|
||||||
m25p16_init(IO_TAG_NONE);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
flashfsInit();
|
flashfsInit();
|
||||||
|
|
|
@ -45,6 +45,34 @@
|
||||||
// alternative defaults settings for AlienFlight targets
|
// alternative defaults settings for AlienFlight targets
|
||||||
void targetConfiguration(master_t *config)
|
void targetConfiguration(master_t *config)
|
||||||
{
|
{
|
||||||
|
/* depending on revision ... depends on the LEDs to be utilised. */
|
||||||
|
if (hardwareRevision == AFF3_REV_1) {
|
||||||
|
config->statusLedConfig.polarity = 0
|
||||||
|
#ifdef LED0_A_INVERTED
|
||||||
|
| BIT(3)
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_A_INVERTED
|
||||||
|
| BIT(4)
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_A_INVERTED
|
||||||
|
| BIT(5)
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
|
||||||
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
|
config->statusLedConfig.ledTags[i] = IO_TAG_NONE;
|
||||||
|
}
|
||||||
|
#ifdef LED0_A
|
||||||
|
config->statusLedConfig.ledTags[0] = IO_TAG(LED0_A);
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_A
|
||||||
|
config->statusLedConfig.ledTags[1] = IO_TAG(LED1_A);
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_A
|
||||||
|
config->statusLedConfig.ledTags[2] = IO_TAG(LED2_A);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
config->rxConfig.spektrum_sat_bind = 5;
|
config->rxConfig.spektrum_sat_bind = 5;
|
||||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||||
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
|
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||||
|
|
48
src/main/target/ALIENFLIGHTF3/initialisation.c
Normal file
48
src/main/target/ALIENFLIGHTF3/initialisation.c
Normal file
|
@ -0,0 +1,48 @@
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
|
void targetBusInit(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_SPI
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
|
spiInit(SPIDEV_1);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
|
spiInit(SPIDEV_2);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_3
|
||||||
|
if (hardwareRevision == AFF3_REV_2) {
|
||||||
|
spiInit(SPIDEV_3);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_4
|
||||||
|
spiInit(SPIDEV_4);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_I2C
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
|
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
|
|
|
@ -85,7 +85,8 @@ void updateHardwareRevision(void)
|
||||||
/*
|
/*
|
||||||
if flash exists on PB3 then Rev1
|
if flash exists on PB3 then Rev1
|
||||||
*/
|
*/
|
||||||
if (m25p16_init(IO_TAG(PB3))) {
|
flashConfig_t flashConfig = { .csTag = IO_TAG(PB3) };
|
||||||
|
if (m25p16_init(&flashConfig)) {
|
||||||
hardwareRevision = BJF4_REV1;
|
hardwareRevision = BJF4_REV1;
|
||||||
} else {
|
} else {
|
||||||
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);
|
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);
|
||||||
|
|
36
src/main/target/CJMCU/initialisation.c
Normal file
36
src/main/target/CJMCU/initialisation.c
Normal file
|
@ -0,0 +1,36 @@
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
void targetBusInit(void)
|
||||||
|
{
|
||||||
|
#if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
|
||||||
|
spiInit(SPIDEV_1);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||||
|
serialRemovePort(SERIAL_PORT_USART3);
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
}
|
||||||
|
}
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0 PC14
|
||||||
#define LED1 PC13
|
#define LED1 PC13
|
||||||
|
|
|
@ -35,6 +35,8 @@
|
||||||
|
|
||||||
void targetConfiguration(master_t *config)
|
void targetConfiguration(master_t *config)
|
||||||
{
|
{
|
||||||
|
UNUSED(config);
|
||||||
|
|
||||||
#ifdef BEEBRAIN
|
#ifdef BEEBRAIN
|
||||||
// alternative defaults settings for Beebrain target
|
// alternative defaults settings for Beebrain target
|
||||||
config->motorConfig.motorPwmRate = 4000;
|
config->motorConfig.motorPwmRate = 4000;
|
||||||
|
@ -88,9 +90,8 @@ void targetConfiguration(master_t *config)
|
||||||
} else {
|
} else {
|
||||||
config->beeperConfig.isOpenDrain = true;
|
config->beeperConfig.isOpenDrain = true;
|
||||||
config->beeperConfig.isInverted = false;
|
config->beeperConfig.isInverted = false;
|
||||||
|
config->flashConfig.csTag = IO_TAG_NONE;
|
||||||
}
|
}
|
||||||
#else
|
|
||||||
UNUSED(config);
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -127,3 +127,4 @@ const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
44
src/main/target/NAZE/initialisation.c
Normal file
44
src/main/target/NAZE/initialisation.c
Normal file
|
@ -0,0 +1,44 @@
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "io/serial.h"
|
||||||
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
|
void targetBusInit(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_SPI
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
|
spiInit(SPIDEV_2);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (hardwareRevision != NAZE32_SP) {
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
||||||
|
} else {
|
||||||
|
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||||
|
serialRemovePort(SERIAL_PORT_USART3);
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define CLI_MINIMAL_VERBOSITY
|
#define CLI_MINIMAL_VERBOSITY
|
||||||
|
|
||||||
|
@ -65,17 +66,12 @@
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
||||||
#define NAZE_SPI_INSTANCE SPI2
|
#define NAZE_SPI_INSTANCE SPI2
|
||||||
#define NAZE_SPI_CS_GPIO GPIOB
|
|
||||||
#define NAZE_SPI_CS_PIN PB12
|
#define NAZE_SPI_CS_PIN PB12
|
||||||
#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
|
|
||||||
|
|
||||||
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
|
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
|
||||||
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
|
|
||||||
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
|
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
|
||||||
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
|
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
|
||||||
|
|
||||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
|
|
||||||
#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
|
|
||||||
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
|
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
|
||||||
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
|
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
|
||||||
|
|
||||||
|
|
|
@ -98,6 +98,7 @@
|
||||||
#define SOFTSERIAL_2_TIMER TIM3
|
#define SOFTSERIAL_2_TIMER TIM3
|
||||||
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
||||||
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||||
|
#define SONAR_SOFTSERIAL2_EXCLUSIVE
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||||
|
|
|
@ -88,6 +88,7 @@
|
||||||
#define SOFTSERIAL_1_TIMER TIM2
|
#define SOFTSERIAL_1_TIMER TIM2
|
||||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
|
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
|
||||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
|
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
|
||||||
|
#define SONAR_SOFTSERIAL1_EXCLUSIVE
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||||
|
@ -129,13 +130,6 @@
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define WS2811_PIN PA8
|
|
||||||
#define WS2811_TIMER 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 WS2811_TIMER_GPIO_AF GPIO_AF_6
|
|
||||||
|
|
||||||
#define TRANSPONDER
|
#define TRANSPONDER
|
||||||
|
|
||||||
|
|
|
@ -71,7 +71,7 @@
|
||||||
#define SOFTSERIAL_1_TIMER TIM3
|
#define SOFTSERIAL_1_TIMER TIM3
|
||||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
||||||
|
#define SONAR_SOFTSERIAL1_EXCLUSIVE
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue