Merge pull request #1745 from blckmn/main_no_target

Main no target
This commit is contained in:
Martin Budden 2016-12-11 11:53:25 +01:00 committed by GitHub
commit 87319103ae
21 changed files with 288 additions and 165 deletions

View File

@ -31,6 +31,8 @@
#include "drivers/sonar_hcsr04.h"
#include "drivers/sdcard.h"
#include "drivers/vcd.h"
#include "drivers/light_led.h"
#include "drivers/flash.h"
#include "fc/rc_controls.h"
@ -90,10 +92,12 @@
#define beeperConfig(x) (&masterConfig.beeperConfig)
#define sonarConfig(x) (&masterConfig.sonarConfig)
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
#define statusLedConfig(x) (&masterConfig.statusLedConfig)
#define osdProfile(x) (&masterConfig.osdProfile)
#define vcdProfile(x) (&masterConfig.vcdProfile)
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
#define flashConfig(x) (&masterConfig.flashConfig)
// System-wide
@ -162,6 +166,8 @@ typedef struct master_s {
serialConfig_t serialConfig;
telemetryConfig_t telemetryConfig;
statusLedConfig_t statusLedConfig;
#ifdef USE_PPM
ppmConfig_t ppmConfig;
#endif
@ -226,6 +232,10 @@ typedef struct master_s {
blackboxConfig_t blackboxConfig;
#endif
#ifdef USE_FLASHFS
flashConfig_t flashConfig;
#endif
uint32_t beeper_off_flags;
uint32_t preferred_beeper_off_flags;

View File

@ -18,6 +18,7 @@
#pragma once
#include <stdint.h>
#include "drivers/io_types.h"
typedef struct flashGeometry_s {
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
} flashGeometry_t;
typedef struct flashConfig_s {
ioTag_t csTag;
} flashConfig_t;

View File

@ -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
* 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
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) {
return true;
}
if (csTag) {
m25p16CsPin = IOGetByTag(csTag);
if (flashConfig->csTag) {
m25p16CsPin = IOGetByTag(flashConfig->csTag);
} else {
#ifdef M25P16_CS_PIN
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
#else
return false;
#endif
}
IOInit(m25p16CsPin, OWNER_FLASH_CS, 0);
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);

View File

@ -18,11 +18,11 @@
#pragma once
#include <stdint.h>
#include "io_types.h"
#include "flash.h"
#define M25P16_PAGESIZE 256
bool m25p16_init(ioTag_t csTag);
bool m25p16_init(flashConfig_t *flashConfig);
void m25p16_eraseSector(uint32_t address);
void m25p16_eraseCompletely();

View File

@ -22,82 +22,23 @@
#include "light_led.h"
static const IO_t leds[] = {
#ifdef LED0
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
};
static IO_t leds[LED_NUMBER];
static uint8_t ledPolarity = 0;
uint8_t ledPolarity = 0
#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)
void ledInit(statusLedConfig_t *statusLedConfig)
{
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
if (alternative_led) {
ledOffset = LED_NUMBER;
}
#else
UNUSED(alternative_led);
#endif
LED0_OFF;
LED1_OFF;
LED2_OFF;
ledPolarity = statusLedConfig->polarity;
for (int i = 0; i < LED_NUMBER; i++) {
if (leds[i + ledOffset]) {
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_INDEX(i));
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
if (statusLedConfig->ledTags[i]) {
leds[i] = IOGetByTag(statusLedConfig->ledTags[i]);
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)
{
IOToggle(leds[led + ledOffset]);
IOToggle(leds[led]);
}
void ledSet(int led, bool on)
{
const bool inverted = (1 << (led + ledOffset)) & ledPolarity;
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
const bool inverted = (1 << (led)) & ledPolarity;
IOWrite(leds[led], on ? inverted : !inverted);
}

View File

@ -17,8 +17,15 @@
#pragma once
#include "drivers/io_types.h"
#define LED_NUMBER 3
typedef struct statusLedConfig_s {
ioTag_t ledTags[LED_NUMBER];
uint8_t polarity;
} statusLedConfig_t;
// Helpful macros
#ifdef LED0
# define LED0_TOGGLE ledToggle(0)
@ -50,6 +57,6 @@
# define LED2_ON do {} while(0)
#endif
void ledInit(bool alternative_led);
void ledInit(statusLedConfig_t *statusLedConfig);
void ledToggle(int led);
void ledSet(int led, bool state);

View File

@ -490,6 +490,46 @@ void resetMax7456Config(vcdProfile_t *pVcdProfile)
}
#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)
{
return masterConfig.current_profile_index;
@ -789,6 +829,12 @@ void createDefaultConfig(master_t *config)
}
#endif
#ifdef USE_FLASHFS
resetFlashConfig(&config->flashConfig);
#endif
resetStatusLedConfig(&config->statusLedConfig);
#if defined(TARGET_CONFIG)
targetConfiguration(config);
#endif

View File

@ -124,6 +124,10 @@
#include "build/build_config.h"
#include "build/debug.h"
#ifdef TARGET_BUS_INIT
void targetBusInit(void);
#endif
extern uint8_t motorControlEnable;
#ifdef SOFTSERIAL_LOOPBACK
@ -172,11 +176,7 @@ void init(void)
// Latch active features to be used for feature() in the remainder of init().
latchActiveFeatures();
#ifdef ALIENFLIGHTF3
ledInit(hardwareRevision == AFF3_REV_1 ? false : true);
#else
ledInit(false);
#endif
ledInit(&masterConfig.statusLedConfig);
LED2_ON;
#ifdef USE_EXTI
@ -291,7 +291,6 @@ void init(void)
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
#endif
systemState |= SYSTEM_STATE_MOTORS_READY;
#ifdef BEEPER
@ -306,74 +305,48 @@ void init(void)
bstInit(BST_DEVICE);
#endif
#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
#ifdef ALIENFLIGHTF3
if (hardwareRevision == AFF3_REV_2) {
spiInit(SPIDEV_3);
}
#ifdef TARGET_BUS_INIT
targetBusInit();
#else
#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
spiInit(SPIDEV_3);
#endif
#endif
#ifdef USE_SPI_DEVICE_4
#endif
#ifdef USE_SPI_DEVICE_4
spiInit(SPIDEV_4);
#endif
#endif
#endif
#endif
#ifdef VTX
vtxInit();
#ifdef USE_I2C
i2cInit(I2C_DEVICE);
#endif
#endif
#ifdef USE_HARDWARE_REVISION_DETECTION
updateHardwareRevision();
#endif
#if defined(NAZE)
if (hardwareRevision == NAZE32_SP) {
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
} else {
serialRemovePort(SERIAL_PORT_USART3);
}
#ifdef VTX
vtxInit();
#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)) {
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
}
#endif
#if defined(SPRACINGF3MINI) || defined(OMNIBUS) || defined(X_RACERSPI)
#if defined(SONAR) && defined(USE_SOFTSERIAL1)
#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL1)
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
}
#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
/* these can be removed from features! */
@ -383,7 +356,6 @@ void init(void)
adcInit(&masterConfig.adcConfig);
#endif
initBoardAlignment(&masterConfig.boardAlignment);
#ifdef CMS
@ -513,12 +485,8 @@ void init(void)
#endif
#ifdef USE_FLASHFS
#ifdef NAZE
if (hardwareRevision == NAZE32_REV5) {
m25p16_init(IO_TAG_NONE);
}
#elif defined(USE_FLASH_M25P16)
m25p16_init(IO_TAG_NONE);
#if defined(USE_FLASH_M25P16)
m25p16_init(&masterConfig.flashConfig);
#endif
flashfsInit();

View File

@ -45,6 +45,34 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(master_t *config)
{
/* depending on revision ... depends on the LEDs to be utilised. */
if (hardwareRevision == AFF3_REV_2) {
config->statusLedConfig.polarity = 0
#ifdef LED0_A_INVERTED
| BIT(0)
#endif
#ifdef LED1_A_INVERTED
| BIT(1)
#endif
#ifdef LED2_A_INVERTED
| BIT(2)
#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_autoreset = 1;
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default

View 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
}

View File

@ -19,6 +19,7 @@
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define TARGET_CONFIG
#define TARGET_BUS_INIT
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT

View File

@ -85,7 +85,8 @@ void updateHardwareRevision(void)
/*
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;
} else {
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);

View 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);
}
}

View File

@ -19,6 +19,7 @@
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define TARGET_BUS_INIT
#define LED0 PC14
#define LED1 PC13

View File

@ -35,6 +35,8 @@
void targetConfiguration(master_t *config)
{
UNUSED(config);
#ifdef BEEBRAIN
// alternative defaults settings for Beebrain target
config->motorConfig.motorPwmRate = 4000;
@ -88,9 +90,8 @@ void targetConfiguration(master_t *config)
} else {
config->beeperConfig.isOpenDrain = true;
config->beeperConfig.isInverted = false;
config->flashConfig.csTag = IO_TAG_NONE;
}
#else
UNUSED(config);
#endif
}

View File

@ -127,3 +127,4 @@ const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
}
#endif
}

View 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);
}
}
}

View File

@ -19,6 +19,7 @@
#define TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION
#define TARGET_BUS_INIT
//#define CLI_MINIMAL_VERBOSITY
@ -65,17 +66,12 @@
#define USE_SPI_DEVICE_2
#define NAZE_SPI_INSTANCE SPI2
#define NAZE_SPI_CS_GPIO GPIOB
#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:
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
#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_SPI_INSTANCE NAZE_SPI_INSTANCE

View File

@ -98,6 +98,7 @@
#define SOFTSERIAL_2_TIMER TIM3
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
#define SONAR_SOFTSERIAL2_EXCLUSIVE
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA

View File

@ -88,6 +88,7 @@
#define SOFTSERIAL_1_TIMER TIM2
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
#define SONAR_SOFTSERIAL1_EXCLUSIVE
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
@ -129,13 +130,6 @@
#define RSSI_ADC_PIN PB2
#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

View File

@ -71,7 +71,7 @@
#define SOFTSERIAL_1_TIMER TIM3
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
#define SONAR_SOFTSERIAL1_EXCLUSIVE
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA