1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

Fixes to target config and box modes

This commit is contained in:
Konstantin Sharlaimov (DigitalEntity) 2018-11-19 20:30:32 +01:00
parent e7750fa31a
commit 5e9c2bc87f
41 changed files with 18 additions and 82 deletions

View file

@ -140,11 +140,19 @@ void validateNavConfig(void)
} }
#endif #endif
// Stubs to handle target-specific configs
__attribute__((weak)) void validateAndFixTargetConfig(void) __attribute__((weak)) void validateAndFixTargetConfig(void)
{ {
// Stub __NOP();
} }
__attribute__((weak)) void targetConfiguration(void)
{
__NOP();
}
#ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
#define FIRST_PORT_INDEX 1 #define FIRST_PORT_INDEX 1
#define SECOND_PORT_INDEX 0 #define SECOND_PORT_INDEX 0
@ -329,9 +337,7 @@ void createDefaultConfig(void)
#endif #endif
#endif #endif
#if defined(TARGET_CONFIG)
targetConfiguration(); targetConfiguration();
#endif
} }
void resetConfigs(void) void resetConfigs(void)

View file

@ -337,6 +337,8 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags)
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSDALT3)), BOXOSDALT3); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXOSDALT3)), BOXOSDALT3);
CHECK_ACTIVE_BOX(IS_ENABLED(navigationTerrainFollowingEnabled()), BOXSURFACE); CHECK_ACTIVE_BOX(IS_ENABLED(navigationTerrainFollowingEnabled()), BOXSURFACE);
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBRAKING)), BOXBRAKING); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBRAKING)), BOXBRAKING);
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXUSER1)), BOXUSER1);
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXUSER2)), BOXUSER2);
memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t)); memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t));
for (uint32_t i = 0; i < activeBoxIdCount; i++) { for (uint32_t i = 0; i < activeBoxIdCount; i++) {

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "AFF3" // ALIENFLIGHT F3 #define TARGET_BOARD_IDENTIFIER "AFF3" // ALIENFLIGHT F3
#define TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PB2 #define HW_PIN PB2

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "AFF4" #define TARGET_BOARD_IDENTIFIER "AFF4"
#define TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13 #define HW_PIN PC13

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "AFF7" #define TARGET_BOARD_IDENTIFIER "AFF7"
#define TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC13 #define HW_PIN PC13

View file

@ -25,7 +25,6 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "flight/mixer.h" #include "flight/mixer.h"
@ -40,4 +39,3 @@ void targetConfiguration(void)
motorConfigMutable()->minthrottle = 1075; motorConfigMutable()->minthrottle = 1075;
motorConfigMutable()->maxthrottle = 1950; motorConfigMutable()->maxthrottle = 1950;
} }
#endif

View file

@ -160,8 +160,6 @@
#define SERIALRX_UART SERIAL_PORT_USART1 #define SERIALRX_UART SERIAL_PORT_USART1
#define SMARTAUDIO_UART SERIAL_PORT_USART2 #define SMARTAUDIO_UART SERIAL_PORT_USART2
#define TARGET_CONFIG
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
// Number of available PWM outputs // Number of available PWM outputs

View file

@ -17,14 +17,10 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "sensors/battery.h" #include "sensors/battery.h"
void targetConfiguration(void) void targetConfiguration(void)
{ {
batteryMetersConfigMutable()->current.scale = 20; batteryMetersConfigMutable()->current.scale = 20;
} }
#endif

View file

@ -20,9 +20,6 @@
#define TARGET_BOARD_IDENTIFIER "BFF3" #define TARGET_BOARD_IDENTIFIER "BFF3"
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define TARGET_CONFIG
#define BEEPER PC15 #define BEEPER PC15
#define BEEPER_INVERTED #define BEEPER_INVERTED

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "BJF4" #define TARGET_BOARD_IDENTIFIER "BJF4"
#define TARGET_CONFIG
#define USBD_PRODUCT_STRING "BlueJayF4" #define USBD_PRODUCT_STRING "BlueJayF4"

View file

@ -139,8 +139,6 @@
#define USE_RANGEFINDER_VL53L0X #define USE_RANGEFINDER_VL53L0X
#define VL53L0X_I2C_BUS BUS_I2C3 #define VL53L0X_I2C_BUS BUS_I2C3
#define TARGET_CONFIG
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define DEFAULT_RX_TYPE RX_TYPE_SERIAL

View file

@ -122,8 +122,6 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_CONFIG
// Number of available PWM outputs // Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 10 #define MAX_PWM_OUTPUT_PORTS 10

View file

@ -19,8 +19,6 @@
#define TARGET_BOARD_IDENTIFIER "FLCR" // FaLCoRre #define TARGET_BOARD_IDENTIFIER "FLCR" // FaLCoRre
#define TARGET_CONFIG
#define LED0 PC2 #define LED0 PC2
#define LED1 PB11 #define LED1 PB11

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "FF35" #define TARGET_BOARD_IDENTIFIER "FF35"
#define TARGET_CONFIG
#define USBD_PRODUCT_STRING "FURIOUS F35-LIGHTNING" #define USBD_PRODUCT_STRING "FURIOUS F35-LIGHTNING"

View file

@ -20,13 +20,9 @@
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "fc/config.h" #include "fc/config.h"
#include "config/feature.h" #include "config/feature.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "hardware_revision.h" #include "hardware_revision.h"
void targetConfiguration(void) void targetConfiguration(void)
@ -37,4 +33,3 @@ void targetConfiguration(void)
rxConfigMutable()->halfDuplex = false; rxConfigMutable()->halfDuplex = false;
} }
#endif

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "FORT" #define TARGET_BOARD_IDENTIFIER "FORT"
#define USBD_PRODUCT_STRING "FortiniF4" #define USBD_PRODUCT_STRING "FortiniF4"
#define TARGET_CONFIG
#define USE_HARDWARE_REVISION_DETECTION #define USE_HARDWARE_REVISION_DETECTION
#define HW_PIN PC14 #define HW_PIN PC14
/*--------------LED----------------*/ /*--------------LED----------------*/

View file

@ -20,13 +20,9 @@
#include <platform.h> #include <platform.h>
#ifdef USE_TARGET_CONFIG
#include "rx/rx.h" #include "rx/rx.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#define CURRENTSCALE 250 #define CURRENTSCALE 250
void targetConfiguration(void) void targetConfiguration(void)
@ -35,4 +31,3 @@ void targetConfiguration(void)
telemetryConfigMutable()->smartportUartUnidirectional = true; telemetryConfigMutable()->smartportUartUnidirectional = true;
batteryMetersConfigMutable()->current.scale = CURRENTSCALE; batteryMetersConfigMutable()->current.scale = CURRENTSCALE;
} }
#endif

View file

@ -23,7 +23,6 @@
#define TARGET_BOARD_IDENTIFIER "PIK4" #define TARGET_BOARD_IDENTIFIER "PIK4"
#define USBD_PRODUCT_STRING "PikoF4" #define USBD_PRODUCT_STRING "PikoF4"
#endif #endif
#define USE_TARGET_CONFIG
/*--------------LED----------------*/ /*--------------LED----------------*/
#if defined(FF_PIKOF4OSD) #if defined(FF_PIKOF4OSD)
#define LED0 PB5 #define LED0 PB5

View file

@ -25,7 +25,6 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "drivers/io.h" #include "drivers/io.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "io/serial.h" #include "io/serial.h"
@ -34,4 +33,3 @@ void targetConfiguration(void)
{ {
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
} }
#endif

View file

@ -172,7 +172,6 @@
#define SERIALRX_UART SERIAL_PORT_USART1 #define SERIALRX_UART SERIAL_PORT_USART1
#define SMARTAUDIO_UART SERIAL_PORT_USART4 #define SMARTAUDIO_UART SERIAL_PORT_USART4
#define TARGET_CONFIG
#define CURRENT_METER_SCALE 175 #define CURRENT_METER_SCALE 175
#define CURRENT_METER_OFFSET 326 #define CURRENT_METER_OFFSET 326

View file

@ -18,7 +18,6 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "drivers/io.h" #include "drivers/io.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "io/serial.h" #include "io/serial.h"
@ -28,4 +27,3 @@ void targetConfiguration(void)
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
rxConfigMutable()->rssi_channel = 8; rxConfigMutable()->rssi_channel = 8;
} }
#endif

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "FRF3" #define TARGET_BOARD_IDENTIFIER "FRF3"
#define TARGET_CONFIG
#define LED0_PIN PB3 #define LED0_PIN PB3
#define BEEPER PC15 #define BEEPER PC15

View file

@ -18,7 +18,6 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "drivers/io.h" #include "drivers/io.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "io/serial.h" #include "io/serial.h"
@ -28,4 +27,3 @@ void targetConfiguration(void)
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
rxConfigMutable()->rssi_channel = 8; rxConfigMutable()->rssi_channel = 8;
} }
#endif

View file

@ -17,7 +17,6 @@
#define TARGET_BOARD_IDENTIFIER "FRF4" #define TARGET_BOARD_IDENTIFIER "FRF4"
#define USBD_PRODUCT_STRING "FRSKYF4" #define USBD_PRODUCT_STRING "FRSKYF4"
#define TARGET_CONFIG
#define LED0 PB5 #define LED0 PB5
#define BEEPER PB4 #define BEEPER PB4

View file

@ -27,8 +27,6 @@
#include <platform.h> #include <platform.h>
#ifdef USE_TARGET_CONFIG
#include "io/serial.h" #include "io/serial.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
@ -37,4 +35,3 @@ void targetConfiguration(void)
{ {
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
} }
#endif

View file

@ -31,8 +31,6 @@
# define USBD_PRODUCT_STRING "KakuteF4-V1" # define USBD_PRODUCT_STRING "KakuteF4-V1"
#endif #endif
#define USE_TARGET_CONFIG
#define LED0 PB5 #define LED0 PB5
#define LED1 PB4 #define LED1 PB4
#define LED2 PB6 #define LED2 PB6

View file

@ -20,8 +20,6 @@
#pragma once #pragma once
//#define USE_TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "KTF7" #define TARGET_BOARD_IDENTIFIER "KTF7"
#define USBD_PRODUCT_STRING "KakuteF7" #define USBD_PRODUCT_STRING "KakuteF7"

View file

@ -23,11 +23,11 @@
#include "platform.h" #include "platform.h"
#ifdef USE_TARGET_CONFIG
#include "fc/config.h" #include "fc/config.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
void targetConfiguration(void) { } void targetConfiguration(void)
#endif {
}

View file

@ -19,7 +19,6 @@
#define TARGET_BOARD_IDENTIFIER "MF4S" #define TARGET_BOARD_IDENTIFIER "MF4S"
#define USBD_PRODUCT_STRING "Matek_F405SE" #define USBD_PRODUCT_STRING "Matek_F405SE"
#define TARGET_CONFIG
#define LED0 PA14 //Blue #define LED0 PA14 //Blue
#define LED1 PA13 //Green #define LED1 PA13 //Green

View file

@ -18,9 +18,6 @@
#pragma once #pragma once
#define USE_TARGET_CONFIG
#define USE_TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "MF7S" #define TARGET_BOARD_IDENTIFIER "MF7S"
#define USBD_PRODUCT_STRING "MatekF722SE" #define USBD_PRODUCT_STRING "MatekF722SE"

View file

@ -25,7 +25,6 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "drivers/io.h" #include "drivers/io.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "io/serial.h" #include "io/serial.h"
@ -36,4 +35,3 @@ void targetConfiguration(void)
ledStripConfigMutable()->ledConfigs[0] = DEFINE_LED(0, 0, COLOR_GREEN, 0, LED_FUNCTION_ARM_STATE, LED_FLAG_OVERLAY(LED_OVERLAY_WARNING), 0); ledStripConfigMutable()->ledConfigs[0] = DEFINE_LED(0, 0, COLOR_GREEN, 0, LED_FUNCTION_ARM_STATE, LED_FLAG_OVERLAY(LED_OVERLAY_WARNING), 0);
// serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
} }
#endif

View file

@ -29,7 +29,6 @@
#define USBD_PRODUCT_STRING "OMNIBUS NEXT" #define USBD_PRODUCT_STRING "OMNIBUS NEXT"
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS // Don't use common busdev descriptors for IMU #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS // Don't use common busdev descriptors for IMU
#define TARGET_CONFIG
// Status LED // Status LED
#define LED0 PB2 #define LED0 PB2

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#define TARGET_CONFIG
#define TARGET_BOARD_IDENTIFIER "SBF4" #define TARGET_BOARD_IDENTIFIER "SBF4"
#define USBD_PRODUCT_STRING "SpeedyBeeF4" #define USBD_PRODUCT_STRING "SpeedyBeeF4"

View file

@ -20,8 +20,6 @@
#include "platform.h" #include "platform.h"
#ifdef TARGET_CONFIG
#include "io/serial.h" #include "io/serial.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
@ -39,4 +37,3 @@ void targetConfiguration(void)
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
//telemetryConfigMutable()->halfDuplex = 1; //telemetryConfigMutable()->halfDuplex = 1;
} }
#endif

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "SP3N" #define TARGET_BOARD_IDENTIFIER "SP3N"
#define TARGET_CONFIG
#define LED0 PB9 #define LED0 PB9
#define LED1 PB2 #define LED1 PB2

View file

@ -20,17 +20,13 @@
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "io/serial.h" #include "io/serial.h"
#include "sensors/barometer.h" #include "sensors/barometer.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
void targetConfiguration(void) void targetConfiguration(void)
{ {
barometerConfigMutable()->baro_hardware = BARO_BMP280; barometerConfigMutable()->baro_hardware = BARO_BMP280;
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything. serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything.
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
} }
#endif

View file

@ -18,7 +18,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "SP4E" #define TARGET_BOARD_IDENTIFIER "SP4E"
#define TARGET_CONFIG
#ifndef SPRACINGF4EVO_REV #ifndef SPRACINGF4EVO_REV
#define SPRACINGF4EVO_REV 2 #define SPRACINGF4EVO_REV 2

View file

@ -18,7 +18,7 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "config/feature.h" #include "config/feature.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "blackbox/blackbox.h" #include "blackbox/blackbox.h"
@ -60,4 +60,3 @@ void targetConfiguration(void)
pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75;
} }
#endif

View file

@ -28,8 +28,6 @@
#define USBD_PRODUCT_STRING "YUPIF4" #define USBD_PRODUCT_STRING "YUPIF4"
#endif #endif
#define TARGET_CONFIG
#define LED0 PB6 #define LED0 PB6
#define LED1 PB4 #define LED1 PB4

View file

@ -18,7 +18,7 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#ifdef TARGET_CONFIG
#include "config/feature.h" #include "config/feature.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "blackbox/blackbox.h" #include "blackbox/blackbox.h"
@ -60,4 +60,3 @@ void targetConfiguration(void)
pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75; pidProfileMutable()->bank_mc.pid[PID_LEVEL].D = 75;
} }
#endif

View file

@ -19,7 +19,6 @@
#pragma once #pragma once
#define TARGET_BOARD_IDENTIFIER "YPF7" #define TARGET_BOARD_IDENTIFIER "YPF7"
#define USBD_PRODUCT_STRING "YUPIF7" #define USBD_PRODUCT_STRING "YUPIF7"
#define TARGET_CONFIG
#define LED0 PB4 #define LED0 PB4