mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
Target update: AlienWhoop V2.1 blackbox via dataflash (#5723)
This commit is contained in:
parent
fb3b41ca0e
commit
39fec69fb0
3 changed files with 20 additions and 18 deletions
|
@ -67,7 +67,7 @@ void targetConfiguration(void)
|
|||
{
|
||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfigMutable()->minthrottle = 1080;
|
||||
motorConfigMutable()->minthrottle = 1020;
|
||||
motorConfigMutable()->maxthrottle = 2000;
|
||||
}
|
||||
|
||||
|
@ -76,8 +76,8 @@ void targetConfiguration(void)
|
|||
rxConfigMutable()->spektrum_sat_bind = 5;
|
||||
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
|
||||
parseRcChannels("TAER1234", rxConfigMutable());
|
||||
#if defined(ALIENWHOOPF4)
|
||||
rxConfigMutable()->serialrx_inverted = true; // TODO: what to do about F4 inversion?
|
||||
#if defined(ALIENWHOOPF7)
|
||||
rxConfigMutable()->serialrx_inverted = true;
|
||||
#endif
|
||||
|
||||
beeperOffSet((BEEPER_BAT_CRIT_LOW | BEEPER_BAT_LOW | BEEPER_RX_SET) ^ BEEPER_GYRO_CALIBRATED);
|
||||
|
@ -91,10 +91,11 @@ void targetConfiguration(void)
|
|||
barometerConfigMutable()->baro_hardware = BARO_NONE;
|
||||
#endif
|
||||
|
||||
compassConfigMutable()->mag_hardware = MAG_DEFAULT;
|
||||
compassConfigMutable()->mag_hardware = MAG_NONE;
|
||||
|
||||
/* F4 (especially overclocked) and F7 ALIENWHOOP perform splendidly with 32kHz gyro enabled */
|
||||
gyroConfigMutable()->gyro_use_32khz = 1;
|
||||
/* Default to 32kHz enabled at 16/16 */
|
||||
gyroConfigMutable()->gyro_use_32khz = 1; // enable 32kHz sampling
|
||||
gyroConfigMutable()->gyroMovementCalibrationThreshold = 200; // aka moron_threshold
|
||||
gyroConfigMutable()->gyro_sync_denom = 2; // 16kHz gyro
|
||||
pidConfigMutable()->pid_process_denom = 1; // 16kHz PID
|
||||
|
||||
|
@ -120,7 +121,7 @@ void targetConfiguration(void)
|
|||
|
||||
/* Setpoints */
|
||||
pidProfile->dtermSetpointWeight = 100;
|
||||
pidProfile->setpointRelaxRatio = 100; // default to snappy for racers
|
||||
pidProfile->setpointRelaxRatio = 100;
|
||||
|
||||
/* Throttle PID Attenuation (TPA) */
|
||||
pidProfile->itermThrottleThreshold = 400;
|
||||
|
@ -143,7 +144,7 @@ void targetConfiguration(void)
|
|||
|
||||
/* Throttle PID Attenuation (TPA) */
|
||||
controlRateConfig->dynThrPID = 0; // tpa_rate off
|
||||
controlRateConfig->tpa_breakpoint = 1600;
|
||||
controlRateConfig->tpa_breakpoint = 1650;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -109,6 +109,13 @@
|
|||
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
|
||||
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||
|
||||
/* BLACKBOX dataflash available as of V2.1 -- did not exist on V1 and V2 */
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_CS_PIN SPI3_NSS_PIN
|
||||
#define M25P16_SPI_INSTANCE SPI3
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
/* Motion Processing Unit (MPU) - Invensense 6-axis MPU-6500 or 9-axis MPU-9250
|
||||
*/
|
||||
// Interrupt
|
||||
|
@ -172,7 +179,7 @@
|
|||
#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
|
||||
// UART5 async only on F4 ... PB3 and PB4 used by SPI3
|
||||
//#define UART5_TX_PIN PB3 // PC12
|
||||
//#define UART5_RX_PIN PB4 // PD2
|
||||
|
||||
|
@ -185,7 +192,7 @@
|
|||
#define BINDPLUG_PIN PC13 // PC13 Current Limited (3 mA). Not suitable for LED/Beeper
|
||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||
#define RX_CHANNELS_TAER //RX_CHANNELS_AETR
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM1024 //SERIALRX_SBUS
|
||||
#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 //SERIALRX_SBUS
|
||||
|
||||
/* Defaults - What do we want out of the box?
|
||||
*/
|
||||
|
@ -195,13 +202,6 @@
|
|||
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP ) // TODO FEATURE_OSD for V3 board ... FEATURE_TELEMETRY changes bind pin from rx to tx
|
||||
#endif
|
||||
|
||||
/* OSD currently dependent upon CMS, SMARTAUDIO, TRAMP
|
||||
#undef USE_VTX_COMMON
|
||||
#undef USE_VTX_CONTROL
|
||||
#undef USE_VTX_SMARTAUDIO
|
||||
#undef USE_VTX_TRAMP
|
||||
*/
|
||||
|
||||
/* OLED Support
|
||||
*/
|
||||
#if defined(BREADBOARD)
|
||||
|
|
|
@ -15,12 +15,13 @@ else
|
|||
endif
|
||||
endif
|
||||
|
||||
FEATURES += VCP
|
||||
FEATURES += ONBOARDFLASH VCP
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/compass/compass_ak8963.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/max7456.c \
|
||||
io/osd.c
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue