diff --git a/make/release.mk b/make/release.mk index 29c53b3a8f5..405ed64ca11 100644 --- a/make/release.mk +++ b/make/release.mk @@ -1,7 +1,7 @@ RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD RELEASE_TARGETS += COLIBRI_RACE LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY -RELEASE_TARGETS += QUANTON REVO SPARKY2 YUPIF4 KROOZX PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 +RELEASE_TARGETS += QUANTON REVO SPARKY2 YUPIF4 YUPIF4R2 YUPIF4MINI KROOZX PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 RELEASE_TARGETS += ALIENFLIGHTNGF7 RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4 @@ -12,6 +12,6 @@ RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPR RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 FIREWORKSV2 RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4V3 OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO -RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT +RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF405SE diff --git a/src/main/target/YUPIF4/README.md b/src/main/target/YUPIF4/README.md index 2ece9a1336f..d6783af1950 100644 --- a/src/main/target/YUPIF4/README.md +++ b/src/main/target/YUPIF4/README.md @@ -39,3 +39,7 @@ This board is available in the shop FR Website : http://www.yupif4.com ![YuPiF4 - Logo](http://www.yupif4.com/imgs/YuPiF4.jpg) + + +Test YupiFc https://www.facebook.com/jimmy.mix/videos/10214800834801662/ +https://www.facebook.com/jimmy.mix/videos/10214893753404569/ diff --git a/src/main/target/YUPIF4/YUPIF4MINI.mk b/src/main/target/YUPIF4/YUPIF4MINI.mk new file mode 100644 index 00000000000..de18f71abd3 --- /dev/null +++ b/src/main/target/YUPIF4/YUPIF4MINI.mk @@ -0,0 +1 @@ +#YUPIF4MINI diff --git a/src/main/target/YUPIF4/YUPIF4R2.mk b/src/main/target/YUPIF4/YUPIF4R2.mk new file mode 100644 index 00000000000..aec79b6c94d --- /dev/null +++ b/src/main/target/YUPIF4/YUPIF4R2.mk @@ -0,0 +1 @@ +#YUPIF4R2 diff --git a/src/main/target/YUPIF4/config.c b/src/main/target/YUPIF4/config.c index 6f21bd0f4c9..62134ebace4 100644 --- a/src/main/target/YUPIF4/config.c +++ b/src/main/target/YUPIF4/config.c @@ -17,54 +17,47 @@ #include #include - #include - #ifdef TARGET_CONFIG +#include "config/feature.h" +#include "drivers/pwm_output.h" #include "blackbox/blackbox.h" #include "fc/config.h" +#include "fc/controlrate_profile.h" +#include "fc/rc_controls.h" +#include "fc/rc_modes.h" +#include "io/serial.h" +#include "rx/rx.h" +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/compass.h" +#include "sensors/boardalignment.h" #include "flight/pid.h" -#include "telemetry/telemetry.h" - -#include "hardware_revision.h" - - +#include "flight/mixer.h" +#include "flight/servos.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "drivers/sound_beeper.h" +#include "navigation/navigation.h" -// alternative defaults settings for YuPiF4 targets void targetConfiguration(void) { - /* Changes depending on versions */ - if (hardwareRevision == YUPIF4_RACE3) { - beeperDevConfigMutable()->ioTag = IO_TAG(PB14); - telemetryConfigMutable()->halfDuplex = false; - - } else if (hardwareRevision == YUPIF4_RACE2) { - beeperDevConfigMutable()->ioTag = IO_TAG(PB14); - - } else if (hardwareRevision == YUPIF4_MINI) { - beeperDevConfigMutable()->frequency = 0; - blackboxConfigMutable()->device = BLACKBOX_DEVICE_NONE; - adcConfigMutable()->current.enabled = 0; - - } else if (hardwareRevision == YUPIF4_NAV) { - beeperDevConfigMutable()->ioTag = IO_TAG(PB14); - - } else { - adcConfigMutable()->current.enabled = 0; - } - /* Specific PID values for YupiF4 */ - for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) { - pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex); + setConfigProfile(0); + pidProfileMutable()->bank_mc.pid[PID_ROLL].P = 30; + pidProfileMutable()->bank_mc.pid[PID_ROLL].I = 45; + pidProfileMutable()->bank_mc.pid[PID_ROLL].D = 20; + pidProfileMutable()->bank_mc.pid[PID_PITCH].P = 30; + pidProfileMutable()->bank_mc.pid[PID_PITCH].I = 50; + pidProfileMutable()->bank_mc.pid[PID_PITCH].D = 20; + pidProfileMutable()->bank_mc.pid[PID_YAW].P = 40; + pidProfileMutable()->bank_mc.pid[PID_YAW].I = 50; + pidProfileMutable()->bank_mc.pid[PID_YAW].D = 0; + pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20; + pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10; + pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; - pidProfile->pid[PID_ROLL].P = 30; - pidProfile->pid[PID_ROLL].I = 45; - pidProfile->pid[PID_ROLL].D = 20; - pidProfile->pid[PID_PITCH].P = 30; - pidProfile->pid[PID_PITCH].I = 50; - pidProfile->pid[PID_PITCH].D = 20; - pidProfile->pid[PID_YAW].P = 40; - pidProfile->pid[PID_YAW].I = 50; - } } #endif diff --git a/src/main/target/YUPIF4/hardware_revision.c b/src/main/target/YUPIF4/hardware_revision.c deleted file mode 100644 index 5ee99e7b5bc..00000000000 --- a/src/main/target/YUPIF4/hardware_revision.c +++ /dev/null @@ -1,74 +0,0 @@ -/* - * 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 . - */ - -#include -#include -#include - -#include "platform.h" - -#include "build/build_config.h" - -#include "drivers/io.h" -#include "drivers/time.h" -#include "drivers/bus_spi.h" - -#include "hardware_revision.h" - -uint8_t hardwareRevision = UNKNOWN; - -void detectHardwareRevision(void) -{ - IO_t pin1 = IOGetByTag(IO_TAG(PC13)); - IOInit(pin1, OWNER_SYSTEM, RESOURCE_INPUT, 1); - IOConfigGPIO(pin1, IOCFG_IPU); - - IO_t pin2 = IOGetByTag(IO_TAG(PC14)); - IOInit(pin2, OWNER_SYSTEM, RESOURCE_INPUT, 1); - IOConfigGPIO(pin2, IOCFG_IPU); - - IO_t pin3 = IOGetByTag(IO_TAG(PC15)); - IOInit(pin3, OWNER_SYSTEM, RESOURCE_INPUT, 1); - IOConfigGPIO(pin3, IOCFG_IPU); - - // Check hardware revision - delayMicroseconds(10); // allow configuration to settle - - /* - Hardware pins : Pin1 = PC13 / Pin2 = PC14 / Pin3 = PC15 - no Hardware pins tied to ground => Race V1 - if Pin 1 is the only one tied to ground => Mini - if Pin 2 is the only one tied to ground => Race V2 - if Pin 2 and Pin 1 are tied to ground => Race V3 - if Pin 3 is the only one tied to ground => Navigation - Other combinations available for potential evolutions - */ - if (!IORead(pin1) && IORead(pin2)) { - hardwareRevision = YUPIF4_MINI; - } else if (IORead(pin1) && !IORead(pin2)) { - hardwareRevision = YUPIF4_RACE2; - } else if (!IORead(pin1) && !IORead(pin2)) { - hardwareRevision = YUPIF4_RACE3; - } else if (!IORead(pin3)) { - hardwareRevision = YUPIF4_NAV; - } else { - hardwareRevision = YUPIF4_RACE1; - } -} - -void updateHardwareRevision(void) { -} diff --git a/src/main/target/YUPIF4/hardware_revision.h b/src/main/target/YUPIF4/hardware_revision.h deleted file mode 100644 index 7a167ea0434..00000000000 --- a/src/main/target/YUPIF4/hardware_revision.h +++ /dev/null @@ -1,31 +0,0 @@ -/* - * 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 . - */ -#pragma once - -typedef enum yupif4HardwareRevision_t { - UNKNOWN = 0, - YUPIF4_RACE1, // Race V1 - YUPIF4_RACE2, // Race V2 - YUPIF4_RACE3, // Race V3 - YUPIF4_MINI, // Mini - YUPIF4_NAV // Navigation -} yupif4HardwareRevision_e; - -extern uint8_t hardwareRevision; - -void detectHardwareRevision(void); -void updateHardwareRevision(void); diff --git a/src/main/target/YUPIF4/target.c b/src/main/target/YUPIF4/target.c index a143156a3c0..201f054e9c6 100644 --- a/src/main/target/YUPIF4/target.c +++ b/src/main/target/YUPIF4/target.c @@ -30,6 +30,15 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM5, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, { TIM5, IO_TAG(PA3), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, { TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, +#if defined (YUPIF4R2) { TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED }, { TIM12, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_TIM12, TIM_USE_BEEPER }, +#elif (YUPIF4MINI) + { TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, + { TIM3, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_BEEPER }, +#else + { TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED }, + { TIM3, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_BEEPER }, +#endif }; + diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h index bf039b972ee..bef9e64dc97 100644 --- a/src/main/target/YUPIF4/target.h +++ b/src/main/target/YUPIF4/target.h @@ -16,17 +16,36 @@ */ #pragma once + +#if defined (YUPIF4R2) +#define TARGET_BOARD_IDENTIFIER "YPF4R2" +#define USBD_PRODUCT_STRING "YUPIF4R2" +#elif (YUPIF4MINI) +#define TARGET_BOARD_IDENTIFIER "YPF4M" +#define USBD_PRODUCT_STRING "YUPIF4MINI" +#else #define TARGET_BOARD_IDENTIFIER "YPF4" +#define USBD_PRODUCT_STRING "YUPIF4" +#endif -#define USBD_PRODUCT_STRING "YupiF4" +#define TARGET_CONFIG #define LED0 PB6 #define LED1 PB4 +#if defined(YUPIF4R2) #define BEEPER PB14 +#else +#define BEEPER PC9 +#endif + +#if defined(YUPIF4MINI) +#define BEEPER_INVERTED +#else #define BEEPER_PWM #define BEEPER_INVERTED #define BEEPER_PWM_FREQUENCY 3150 +#endif #define INVERTER_PIN_UART6 PB15 @@ -73,6 +92,8 @@ #define MAX7456_SPI_BUS BUS_SPI1 #define MAX7456_CS_PIN PA14 +#if defined(YUPIF4MINI) +#else #define USE_SDCARD #define USE_SDCARD_SPI3 #define SDCARD_DETECT_INVERTED @@ -83,6 +104,7 @@ #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5 #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CHANNEL DMA_Channel_0 +#endif #define USB_IO #define USE_VCP @@ -155,5 +177,13 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) +#if defined (YUPIF4R2) #define USABLE_TIMER_CHANNEL_COUNT 8 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12)) +#elif (YUPIF4MINI) +#define USABLE_TIMER_CHANNEL_COUNT 8 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8)) +#else +#define USABLE_TIMER_CHANNEL_COUNT 8 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8)) +#endif diff --git a/src/main/target/YUPIF7/config.c b/src/main/target/YUPIF7/config.c index 62cc47a458a..adbd9f97b0e 100644 --- a/src/main/target/YUPIF7/config.c +++ b/src/main/target/YUPIF7/config.c @@ -18,27 +18,46 @@ #include #include #include - -#ifdef USE_TARGET_CONFIG +#ifdef TARGET_CONFIG +#include "config/feature.h" +#include "drivers/pwm_output.h" +#include "blackbox/blackbox.h" #include "fc/config.h" +#include "fc/controlrate_profile.h" +#include "fc/rc_controls.h" +#include "fc/rc_modes.h" +#include "io/serial.h" +#include "rx/rx.h" +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/compass.h" +#include "sensors/boardalignment.h" #include "flight/pid.h" +#include "flight/mixer.h" +#include "flight/servos.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "drivers/sound_beeper.h" +#include "navigation/navigation.h" - -// alternative defaults settings for YuPiF4 targets void targetConfiguration(void) { - /* Specific PID values for YupiF4 */ - for (uint8_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) { - pidProfile_t *pidProfile = pidProfilesMutable(pidProfileIndex); + /* Specific PID values for YupiF7 */ + setConfigProfile(0); + pidProfileMutable()->bank_mc.pid[PID_ROLL].P = 30; + pidProfileMutable()->bank_mc.pid[PID_ROLL].I = 45; + pidProfileMutable()->bank_mc.pid[PID_ROLL].D = 20; + pidProfileMutable()->bank_mc.pid[PID_PITCH].P = 30; + pidProfileMutable()->bank_mc.pid[PID_PITCH].I = 50; + pidProfileMutable()->bank_mc.pid[PID_PITCH].D = 20; + pidProfileMutable()->bank_mc.pid[PID_YAW].P = 40; + pidProfileMutable()->bank_mc.pid[PID_YAW].I = 50; + pidProfileMutable()->bank_mc.pid[PID_YAW].D = 0; + pidProfileMutable()->bank_mc.pid[PID_LEVEL].P = 20; + pidProfileMutable()->bank_mc.pid[PID_LEVEL].I = 10; + pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; - pidProfile->pid[PID_ROLL].P = 30; - pidProfile->pid[PID_ROLL].I = 45; - pidProfile->pid[PID_ROLL].D = 20; - pidProfile->pid[PID_PITCH].P = 30; - pidProfile->pid[PID_PITCH].I = 50; - pidProfile->pid[PID_PITCH].D = 20; - pidProfile->pid[PID_YAW].P = 40; - pidProfile->pid[PID_YAW].I = 50; - } } #endif diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index d31710ae63f..cb32d6580a2 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -15,10 +15,11 @@ * along with Cleanflight. If not, see . */ + #pragma once #define TARGET_BOARD_IDENTIFIER "YPF7" - #define USBD_PRODUCT_STRING "YUPIF7" +#define TARGET_CONFIG #define LED0 PB4 @@ -32,7 +33,7 @@ // Gyro interrupt #define USE_EXTI -#define GYRO_INT_EXTI PC4 +#define GYRO_INT_EXTI PC4 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW @@ -92,7 +93,6 @@ #define USE_ESCSERIAL #define ESCSERIAL_TIMER_TX_HARDWARE 0 -// #define ESCSERIAL_TIMER_TX_PIN PC8 // (Hardware=0, PPM) //SPI ports #define USE_SPI @@ -119,25 +119,25 @@ // OSD #define USE_OSD #define USE_MAX7456 -#define MAX7456_SPI_BUS BUS_SPI1 -#define MAX7456_CS_PIN PA14 +#define MAX7456_SPI_BUS BUS_SPI1 +#define MAX7456_CS_PIN PA14 // Dataflash #define M25P16_CS_PIN SPI3_NSS_PIN -#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_SPI_BUS BUS_SPI3 #define USE_FLASHFS #define USE_FLASH_M25P16 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT // ADC inputs #define USE_ADC -#define ADC_CHANNEL_1_PIN PC0 -#define ADC_CHANNEL_2_PIN PC1 -#define ADC_CHANNEL_3_PIN PC2 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 #define RSSI_ADC_CHANNEL ADC_CHN_1 #define VBAT_ADC_CHANNEL ADC_CHN_2 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 -#define CURRENT_METER_SCALE 235 +#define CURRENT_METER_SCALE 235 // LED Strip can run off Pin 5 (PB1) of the motor outputs #define USE_LED_STRIP @@ -149,8 +149,6 @@ #define WS2811_DMA_CHANNEL DMA_CHANNEL_5 #define WS2811_TIMER_GPIO_AF GPIO_AF3_TIM8 -// ################################################# - // Default configuration #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART6 @@ -160,8 +158,8 @@ // Target IO and timers #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define MAX_PWM_OUTPUT_PORTS 9 -#define TARGET_MOTOR_COUNT 6 +#define MAX_PWM_OUTPUT_PORTS 9 +#define TARGET_MOTOR_COUNT 6 #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff