From 01b489ab09442e8c6529f8472d444f35031aae0a Mon Sep 17 00:00:00 2001 From: "brucesdad13@gmail.com" Date: Fri, 14 Jul 2017 23:43:48 -0400 Subject: [PATCH 1/5] Initial import of ALIENWHOOP target (Charlie's AlienWhoop not AlienFlight NG Whoop) supporting F4 or F7 processors and either the MPU-6500 or MPU-9250. Option for BMP-280 and possible MAX7456 under consideration. Board will be available by the end of July 2017 and second draft prototype is currently being fabricated by OSH Park. This fc is a remix of Lance's open source hardware AlienFlight F3 brushed quad licensed CC BY-SA 4.0. Eagle CAD files and link to order the board via OSH Park will be made available after final testing. Heard a rumor that release cand. was near and wanted to ensure target was ready. ~ Charlie Stevenson --- src/main/target/ALIENWHOOP/ALIENWHOOPF4.mk | 0 src/main/target/ALIENWHOOP/ALIENWHOOPF7.mk | 0 src/main/target/ALIENWHOOP/config.c | 86 ++++++++ src/main/target/ALIENWHOOP/target.c | 53 +++++ src/main/target/ALIENWHOOP/target.h | 235 +++++++++++++++++++++ src/main/target/ALIENWHOOP/target.mk | 25 +++ 6 files changed, 399 insertions(+) create mode 100644 src/main/target/ALIENWHOOP/ALIENWHOOPF4.mk create mode 100644 src/main/target/ALIENWHOOP/ALIENWHOOPF7.mk create mode 100644 src/main/target/ALIENWHOOP/config.c create mode 100644 src/main/target/ALIENWHOOP/target.c create mode 100644 src/main/target/ALIENWHOOP/target.h create mode 100644 src/main/target/ALIENWHOOP/target.mk diff --git a/src/main/target/ALIENWHOOP/ALIENWHOOPF4.mk b/src/main/target/ALIENWHOOP/ALIENWHOOPF4.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/ALIENWHOOP/ALIENWHOOPF7.mk b/src/main/target/ALIENWHOOP/ALIENWHOOPF7.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/ALIENWHOOP/config.c b/src/main/target/ALIENWHOOP/config.c new file mode 100644 index 0000000000..c430cc689c --- /dev/null +++ b/src/main/target/ALIENWHOOP/config.c @@ -0,0 +1,86 @@ +/* + * 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 . + */ + + +/* + + + + + \ | _ _| __| \ |\ \ /| | _ \ _ \ _ \ + _ \ | | _| . | \ \ \ / __ | ( |( |__/ + _/ _\____|___|___|_|\_| \_/\_/ _| _|\___/\___/_| + + + Take me to your leader-board... + + + +*/ + +#include +#include + +#include + +#ifdef TARGET_CONFIG + +#include "common/axis.h" +#include "config/feature.h" +#include "drivers/pwm_esc_detect.h" +#include "flight/mixer.h" +#include "flight/pid.h" +#include "io/serial.h" +#include "rx/rx.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/compass.h" + +#ifdef BRUSHED_MOTORS_PWM_RATE +#undef BRUSHED_MOTORS_PWM_RATE +#endif + +#define BRUSHED_MOTORS_PWM_RATE 666 // 666Hz };-)>~ low PWM rate seems to give better power and cooler motors... + + +void targetConfiguration(void) +{ + if (hardwareMotorType == MOTOR_BRUSHED) { + motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; + motorConfigMutable()->minthrottle = 1080; + motorConfigMutable()->maxthrottle = 2000; + pidConfigMutable()->pid_process_denom = 1; + } + + rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; +#if defined(ALIENWHOOPF4) + rxConfigMutable()->sbus_inversion = 0; // TODO: what to do about F4 inversion? +#else + rxConfigMutable()->sbus_inversion = 1; // invert on F7 +#endif + +/* Breadboard-specific settings for development purposes only + */ +#if defined(BREADBOARD) + boardAlignmentMutable()->pitchDegrees = 90; // vertical breakout board + barometerConfigMutable()->baro_hardware = BARO_DEFAULT; // still testing not on V1 or V2 pcb +#endif + + compassConfigMutable()->mag_hardware = MAG_DEFAULT; +} +#endif + diff --git a/src/main/target/ALIENWHOOP/target.c b/src/main/target/ALIENWHOOP/target.c new file mode 100644 index 0000000000..c6ca4816eb --- /dev/null +++ b/src/main/target/ALIENWHOOP/target.c @@ -0,0 +1,53 @@ +/* + * 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 . + */ + + +/* + + + + + \ | _ _| __| \ |\ \ /| | _ \ _ \ _ \ + _ \ | | _| . | \ \ \ / __ | ( |( |__/ + _/ _\____|___|___|_|\_| \_/\_/ _| _|\___/\___/_| + + + Take me to your leader-board... + + + +*/ + +#include + +#include +#include "drivers/io.h" + +#include "drivers/timer.h" +#include "drivers/timer_def.h" +#include "drivers/dma.h" + +/* Currently only supporting brushed quad configuration e.g. Tiny Whoop. Care must be + * taken to ensure functionality on both F4 and F7 (STM32F405RGT and STM32F722RET) + */ +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), +}; + diff --git a/src/main/target/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h new file mode 100644 index 0000000000..c0f8ced28f --- /dev/null +++ b/src/main/target/ALIENWHOOP/target.h @@ -0,0 +1,235 @@ +/* + * 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 . + */ + + +/* + + + + + \ | _ _| __| \ |\ \ /| | _ \ _ \ _ \ + _ \ | | _| . | \ \ \ / __ | ( |( |__/ + _/ _\____|___|___|_|\_| \_/\_/ _| _|\___/\___/_| + + + Take me to your leader-board... + + + +*/ + +#pragma once + +/* Multi-Arch Support for 168MHz or 216MHz ARM Cortex processors - STM32F405RGT or STM32F7RET + */ +#if defined(ALIENWHOOPF4) +#define TARGET_BOARD_IDENTIFIER "AWF4" +#define USBD_PRODUCT_STRING "AlienWhoopF4" +#else +#define TARGET_BOARD_IDENTIFIER "AWF7" +#define USBD_PRODUCT_STRING "AlienWhoopF7" +#endif + +#define TARGET_CONFIG // see config.c for target specific customizations + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT +#define BRUSHED_MOTORS +#define BRUSHED_ESC_AUTODETECT + +/* Visual Alerts - SMD LEDs + */ +#define LED0_PIN PC12 // conflicts UART5 +#define LED1_PIN PD2 // conflicts UART5 + +/* Lost Quad Mode and Alerts - RCX03-787 Low Voltage Active Buzzer + */ +#if defined(V2DRAFT) // a few boards exist with older pinout +#define BEEPER PC13 // PC13... limited... current (3 mA)... +#else +#define BEEPER PA2 // PC13... limited... current (3 mA)... +#endif +#define BEEPER_INVERTED // [and] must not be used [to drive LED etc] + +/* Serial Peripheral Interface (SPI) - Up to 50 Mbit/s on F7 + */ +#define USE_SPI +#define USE_SPI_DEVICE_1 // SPI1 can communicate at up to 42 Mbits/s on F4 +#define USE_SPI_DEVICE_2 // SPI2 and SPI3 can communicate at up to 21 Mbit/s on F4 +#define USE_SPI_DEVICE_3 // All SPIs can be served by the DMA controller. +#if defined(ALIENWHOOPF7) +//TODO: +//#define USE_SPI_DEVICE_4 +//#define USE_SPI_DEVICE_5 +#endif + +#define SPI1_NSS_PIN PA4 // LQFP64 pin 20 (PA4) +#define SPI1_SCK_PIN PA5 // LQFP64 pin 21 (PA5) +#define SPI1_MISO_PIN PA6 // LQFP64 pin 22 (PA6) +#define SPI1_MOSI_PIN PA7 // LQFP64 pin 23 (PA7) + +#define SPI2_NSS_PIN PB12 // LQFP64 pin 33 (PB12) +#define SPI2_SCK_PIN PB13 // LQFP64 pin 34 (PB13) +#define SPI2_MISO_PIN PB14 // LQFP64 pin 35 (PB14) +#define SPI2_MOSI_PIN PB15 // LQFP64 pin 36 (PB15) + +#define SPI3_NSS_PIN PA15 // LQFP64 pin 50 (PA15) +//#define SPI3_SCK_PIN PC10 // LQFP64 pin 51 (PC10) +//#define SPI3_MISO_PIN PC11 // LQFP64 pin 52 (PC11) +//#define SPI3_MOSI_PIN PC12 // LQFP64 pin 53 (PC12) +#define SPI3_SCK_PIN PB3 // LQFP64 pin 55 (PB3) +#define SPI3_MISO_PIN PB4 // LQFP64 pin 56 (PB4) +#define SPI3_MOSI_PIN PB5 // LQFP64 pin 57 (PB5) + +#if defined(ALIENWHOOPF7) +//TODO: define SPI4 and SPI5 for F7 target +//#define SPI4_NSS_PIN +//#define SPI4_SCK_PIN +//#define SPI4_MISO_PIN +//#define SPI4_MOSI_PIN +//#define SPI5_NSS_PIN +//#define SPI5_SCK_PIN +//#define SPI5_MISO_PIN +//#define SPI5_MOSI_PIN +#endif + +/* Motion Processing Unit (MPU) - Invensense 6-axis MPU-6500 or 9-axis MPU-9250 + */ +// Interrupt +#define USE_EXTI +#define MPU_INT_EXTI PC14 +// MPU +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW +// MAG +#define MAG +#define USE_MAG_AK8963 +#define MAG_AK8963_ALIGN CW0_DEG +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH +// GYRO +#define GYRO +#define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW0_DEG +// ACC +#define ACC +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW0_DEG + +/* Optional Digital Pressure Sensor (barometer) - Bosch BMP280 + * TODO: not implemented on V1 or V2 pcb + */ +#define BARO +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define BMP280_SPI_INSTANCE SPI3 +#define BMP280_CS_PIN SPI3_NSS_PIN + +/* Serial ports etc. + */ +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 + +#define SERIAL_PORT_COUNT 6 + +// USART1 +#define UART1_TX_PIN PA9 // PB1 INCOMPAT F4 -> F7 +#define UART1_RX_PIN PA10 // PB0 INCOMPAT F4 -> F7 + +// USART2 +#define UART2_TX_PIN PA2 //PA12 +#define UART2_RX_PIN PA3 //PA13 + +// USART3 +#define UART3_TX_PIN PC10 // PB10 INCOMPAT F4 -> F7 +#define UART3_RX_PIN PC11 // PB11 INCOMPAT F4 -> F7 + +// UART4 async only on F4 +#define UART4_TX_PIN PA0 // PC10 currently used by USART3 +#define UART4_RX_PIN PA1 // PC11 currently used by USART3 + +// UART5 async only on F4 +//#define UART5_TX_PIN PB3 // PC12 +//#define UART5_RX_PIN PB4 // PD2 + +/* Receiver - e.g. FrSky XM/XM+ or Spektrum/Lemon DSM/DSMX capable of 3.3V + */ +/* Assume Spektrum following defines inherited from common_fc_pre.h: +//#define USE_SERIALRX_SPEKTRUM +//#define USE_SPEKTRUM_BIND +//#define USE_SPEKTRUM_BIND_PLUG +*/ +#if defined(V2DRAFT) // a few of these boards still exist +#define BINDPLUG_PIN PB14 +#define SPEKTRUM_BIND_PIN PA3 +#define SERIALRX_UART SERIAL_PORT_USART2 +#define RX_CHANNELS_AETR // FrSky AETR TAER SpektrumRC +#else +#define BINDPLUG_PIN PC13 // formerly used for beeper (erroneously) on V1 pcb +#define SPEKTRUM_BIND_PIN UART3_RX_PIN +#define SERIALRX_UART SERIAL_PORT_USART3 +#define RX_CHANNELS_TAER //RX_CHANNELS_AETR +#endif +#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM1024 //SERIALRX_SBUS + +/* Defaults - What do we want out of the box? + */ +#if defined(BREADBOARD) +#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP ) +#else +#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP | FEATURE_FAILSAFE) // FEATURE_TELEMETRY changes bind pin from rx to tx +#endif + +/* OLED Support + */ +#if defined(BREADBOARD) +#define CMS +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE (I2CDEV_1) +#define USE_I2C_PULLUP +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 +#else +#undef CMS +#undef USE_I2C +#endif + +/* MCU Pin Mapping - LPFQ64 Flags + */ +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#if defined(ALIENWHOOPF4) +// STM32F405RGT +#define TARGET_IO_PORTD (BIT(2)) +#else +// STM32F722RET +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#endif + +/* Timers + */ +#define USABLE_TIMER_CHANNEL_COUNT 4 +#define USED_TIMERS ( TIM_N(3) | TIM_N(8) ) + diff --git a/src/main/target/ALIENWHOOP/target.mk b/src/main/target/ALIENWHOOP/target.mk new file mode 100644 index 0000000000..2eec8ed063 --- /dev/null +++ b/src/main/target/ALIENWHOOP/target.mk @@ -0,0 +1,25 @@ +# +# +# \ | _ _| __| \ |\ \ /| | _ \ _ \ _ \ +# _ \ | | _| . | \ \ \ / __ | ( |( |__/ +# _/ _\____|___|___|_|\_| \_/\_/ _| _|\___/\___/_| +# +# +ifeq ($(TARGET), ALIENWHOOPF4) +F405_TARGETS += $(TARGET) # STM32F405RGT +else +ifeq ($(TARGET), ALIENWHOOPF7) +F7X2RE_TARGETS += $(TARGET) # STM32F722RET +else +# Nothing to do for generic ALIENWHOOP... an MCU arch should be specified +endif +endif + +FEATURES += VCP + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_spi_bmp280.c \ + drivers/compass/compass_ak8963.c From 4de1f747fe800080687cfab0eff38e489bfa0fdf Mon Sep 17 00:00:00 2001 From: "brucesdad13@gmail.com" Date: Sat, 15 Jul 2017 00:57:06 -0400 Subject: [PATCH 2/5] * Updated Makefile to hopefully appease travis * Undefined VTX-related in target.h.. not currently used on target and caused warnings... ~ Charlie Stevenson --- Makefile | 1 + src/main/target/ALIENWHOOP/target.h | 5 +++++ 2 files changed, 6 insertions(+) diff --git a/Makefile b/Makefile index f415d80fec..2a23099d57 100644 --- a/Makefile +++ b/Makefile @@ -108,6 +108,7 @@ GROUP_1_TARGETS := \ ALIENFLIGHTF3 \ ALIENFLIGHTF4 \ ALIENFLIGHTNGF7 \ + ALIENWHOOP \ ANYFCF7 \ BEEBRAIN \ BEEROTORF4 \ diff --git a/src/main/target/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h index c0f8ced28f..7b17471928 100644 --- a/src/main/target/ALIENWHOOP/target.h +++ b/src/main/target/ALIENWHOOP/target.h @@ -199,6 +199,11 @@ #define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP | FEATURE_FAILSAFE) // FEATURE_TELEMETRY changes bind pin from rx to tx #endif +#undef VTX_COMMON +#undef VTX_CONTROL +#undef VTX_SMARTAUDIO +#undef VTX_TRAMP + /* OLED Support */ #if defined(BREADBOARD) From 60bfe6905fab57b443b2838392629847f1c8d1bc Mon Sep 17 00:00:00 2001 From: "brucesdad13@gmail.com" Date: Sat, 15 Jul 2017 02:23:39 -0400 Subject: [PATCH 3/5] Added list of DUMMY_TARGETS (folder names that aren't actually targets) to be removed from VALID_TARGETS before build. Currently only ALIENWHOOP proposed target falls into this category. It would potentially be a nice way to clean up some of the other targets where only the arch and a few sensors differ.. thoughts? ~ Charlie Stevenson --- Makefile | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 2a23099d57..7abb579799 100644 --- a/Makefile +++ b/Makefile @@ -88,6 +88,7 @@ HSE_VALUE ?= 8000000 FEATURES = OFFICIAL_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3NEO SPRACINGF4EVO STM32F3DISCOVERY +DUMMY_TARGETS := ALIENWHOOP ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) OSD_SLAVE_TARGETS = SPRACINGF3OSD @@ -96,6 +97,7 @@ VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) +VALID_TARGETS := $(filter-out $(DUMMY_TARGETS), $(VALID_TARGETS)) GROUP_1_TARGETS := \ AFROMINI \ @@ -108,7 +110,8 @@ GROUP_1_TARGETS := \ ALIENFLIGHTF3 \ ALIENFLIGHTF4 \ ALIENFLIGHTNGF7 \ - ALIENWHOOP \ + ALIENWHOOPF4 \ + ALIENWHOOPF7 \ ANYFCF7 \ BEEBRAIN \ BEEROTORF4 \ From ec2e764a5500e06bcbf3a0f25939d6b3fce91f92 Mon Sep 17 00:00:00 2001 From: "brucesdad13@gmail.com" Date: Sat, 15 Jul 2017 02:33:35 -0400 Subject: [PATCH 4/5] Changed define name from DUMMY_TARGETS to SKIP_TARGETS per @blckmn request ~ Charlie Stevenson --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 7abb579799..c395487ecc 100644 --- a/Makefile +++ b/Makefile @@ -88,7 +88,7 @@ HSE_VALUE ?= 8000000 FEATURES = OFFICIAL_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3NEO SPRACINGF4EVO STM32F3DISCOVERY -DUMMY_TARGETS := ALIENWHOOP +SKIP_TARGETS := ALIENWHOOP ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) OSD_SLAVE_TARGETS = SPRACINGF3OSD From 7fcc0b0a20b8192ad21c8db26debb92b4a33cd57 Mon Sep 17 00:00:00 2001 From: "brucesdad13@gmail.com" Date: Sat, 15 Jul 2017 02:39:35 -0400 Subject: [PATCH 5/5] Renamed define DUMMY_TARGETS to SKIP_TARGETS in last commit but forgot to update where it was used. No more late night commits :D ~ Charlie Stevenson --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index c395487ecc..e7ffd47375 100644 --- a/Makefile +++ b/Makefile @@ -97,7 +97,7 @@ VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) -VALID_TARGETS := $(filter-out $(DUMMY_TARGETS), $(VALID_TARGETS)) +VALID_TARGETS := $(filter-out $(SKIP_TARGETS), $(VALID_TARGETS)) GROUP_1_TARGETS := \ AFROMINI \