diff --git a/src/main/target/CLRACINGF4/config.c b/src/main/target/CLRACINGF4/config.c new file mode 100644 index 0000000000..20e15c99b4 --- /dev/null +++ b/src/main/target/CLRACINGF4/config.c @@ -0,0 +1,53 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ +#include +#include + +#include "platform.h" +#include "drivers/serial.h" +#include "pg/rx.h" +#include "pg/piniobox.h" +#include "rx/rx.h" +#include "telemetry/telemetry.h" +#include "fc/config.h" +#include "drivers/pwm_output.h" +#include "sensors/gyro.h" +#include "io/vtx.h" +#include "io/ledstrip.h" +#include "fc/config.h" +#include "pg/piniobox.h" +#include "common/axis.h" +#include "sensors/barometer.h" +#include "sensors/compass.h" +#include "sensors/gyro.h" +#include "flight/mixer.h" +#include "flight/pid.h" +#include "drivers/pwm_output.h" + +#ifdef USE_TARGET_CONFIG + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = 39; + motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT600; + gyroConfigMutable()->gyro_sync_denom = 1; // 8kHz gyro + pidConfigMutable()->pid_process_denom = 1; // 8kHz PID +} +#endif diff --git a/src/main/target/CLRACINGF4/target.h b/src/main/target/CLRACINGF4/target.h index b50332c98e..9d6596547f 100644 --- a/src/main/target/CLRACINGF4/target.h +++ b/src/main/target/CLRACINGF4/target.h @@ -24,9 +24,7 @@ #define USBD_PRODUCT_STRING "CLRACINGF4" -#ifdef OPBL -#define USBD_SERIALNUMBER_STRING "0x8020000" // Remove this at the next major release (?) -#endif +#define USE_TARGET_CONFIG #define LED0_PIN PB5 #define USE_BEEPER @@ -132,12 +130,16 @@ #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC #define USE_TRANSPONDER +#define USE_PINIO +#define PINIO1_PIN PA14 // VTX power switcher +#define USE_PINIOBOX + #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_FEATURES ( FEATURE_OSD ) #define CURRENT_METER_SCALE_DEFAULT 250 -#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) +#define TARGET_IO_PORTA (0xffff ) #define TARGET_IO_PORTB (0xffff & ~(BIT(2))) #define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) #define TARGET_IO_PORTD BIT(2) diff --git a/unified_targets/configs/CLRACINGF4.config b/unified_targets/configs/CLRACINGF4.config index a136875ee0..1905c15bc5 100644 --- a/unified_targets/configs/CLRACINGF4.config +++ b/unified_targets/configs/CLRACINGF4.config @@ -36,6 +36,7 @@ resource ADC_RSSI 1 C03 resource ADC_CURR 1 C01 resource SDCARD_CS 1 B12 resource SDCARD_DETECT 1 B07 +resource PINIO 1 A14 resource FLASH_CS 1 B03 resource OSD_CS 1 A15 resource GYRO_EXTI 1 C04 @@ -78,6 +79,9 @@ dma pin B08 0 # master set blackbox_device = SDCARD +set motor_pwm_protocol = DSHOT600 +set pinio_config = 1,1,1,1 +set pinio_box = 39,255,255,255 set current_meter = ADC set battery_meter = ADC set ibata_scale = 250 @@ -89,6 +93,8 @@ set sdcard_spi_bus = 2 set system_hse_mhz = 8 set max7456_spi_bus = 3 set flash_spi_bus = 3 +set gyro_sync_denom = 1 +set pid_process_denom = 1 set gyro_1_bustype = SPI set gyro_1_spibus = 1 set gyro_1_sensor_align = CW0