mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-20 23:05:17 +03:00
Merge branch 'master' into dzikuvx-adaptive-filter
This commit is contained in:
commit
94bd61d00d
9 changed files with 380 additions and 20 deletions
|
@ -54,7 +54,7 @@ This means that practically 4 landing directions can be saved.
|
|||
> [!CAUTION]
|
||||
> The Configuator automatically determines the ground altitude based on databases on the Internet, which may be inaccurate. Please always compare with the measured GPS altitude at the landing site to avoid crashes.
|
||||
|
||||
### Global paramters
|
||||
### Global parameters
|
||||
|
||||
All settings are available via “Advanced Tuning” in the Configurator.
|
||||
|
||||
|
@ -104,7 +104,7 @@ If the altitude of the waypoint and the "Approach Altitude" are different, the a
|
|||
|
||||
## Logic Conditions
|
||||
|
||||
The current landing state can be retrieved via ID 41 in "Flight" (FW Land State). This allows additional actions to be executed according to the landing phases, e.g. deplyoment of the landing flaps.
|
||||
The current landing state can be retrieved via ID 41 in "Flight" (FW Land State). This allows additional actions to be executed according to the landing phases, e.g. deployment of the landing flaps.
|
||||
|
||||
| Returned value | State |
|
||||
| --- | --- |
|
||||
|
|
|
@ -140,6 +140,18 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
|||
// from mixer.c
|
||||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
static const char pidnames[] =
|
||||
"ROLL;"
|
||||
"PITCH;"
|
||||
"YAW;"
|
||||
"ALT;"
|
||||
"Pos;"
|
||||
"PosR;"
|
||||
"NavR;"
|
||||
"LEVEL;"
|
||||
"MAG;"
|
||||
"VEL;";
|
||||
|
||||
typedef enum {
|
||||
MSP_SDCARD_STATE_NOT_PRESENT = 0,
|
||||
MSP_SDCARD_STATE_FATAL = 1,
|
||||
|
@ -480,16 +492,29 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
case MSP_SERVO:
|
||||
sbufWriteData(dst, &servo, MAX_SUPPORTED_SERVOS * 2);
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SERVO_CONFIG:
|
||||
case MSP_SERVO_CONFIGURATIONS:
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
sbufWriteU16(dst, servoParams(i)->min);
|
||||
sbufWriteU16(dst, servoParams(i)->max);
|
||||
sbufWriteU16(dst, servoParams(i)->middle);
|
||||
sbufWriteU8(dst, servoParams(i)->rate);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 255); // used to be forwardFromChannel, not used anymore, send 0xff for compatibility reasons
|
||||
sbufWriteU32(dst, 0); //Input reversing is not required since it can be done on mixer level
|
||||
}
|
||||
break;
|
||||
case MSP_SERVO_MIX_RULES:
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
sbufWriteU8(dst, customServoMixers(i)->targetChannel);
|
||||
sbufWriteU8(dst, customServoMixers(i)->inputSource);
|
||||
sbufWriteU16(dst, customServoMixers(i)->rate);
|
||||
sbufWriteU8(dst, customServoMixers(i)->speed);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 100);
|
||||
sbufWriteU8(dst, 0);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SERVO_MIXER:
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
sbufWriteU8(dst, customServoMixers(i)->targetChannel);
|
||||
|
@ -696,6 +721,12 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
break;
|
||||
|
||||
case MSP_PIDNAMES:
|
||||
for (const char *c = pidnames; *c; c++) {
|
||||
sbufWriteU8(dst, *c);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_MODE_RANGES:
|
||||
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
const modeActivationCondition_t *mac = modeActivationConditions(i);
|
||||
|
@ -859,13 +890,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, currentBatteryProfile->capacity.unit);
|
||||
break;
|
||||
|
||||
case MSP_MOTOR_PINS:
|
||||
// FIXME This is hardcoded and should not be.
|
||||
for (int i = 0; i < 8; i++) {
|
||||
sbufWriteU8(dst, i + 1);
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef USE_GPS
|
||||
case MSP_RAW_GPS:
|
||||
sbufWriteU8(dst, gpsSol.fixType);
|
||||
|
@ -1162,6 +1186,26 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
#endif
|
||||
|
||||
case MSP_OSD_CONFIG:
|
||||
#ifdef USE_OSD
|
||||
sbufWriteU8(dst, OSD_DRIVER_MAX7456); // OSD supported
|
||||
// send video system (AUTO/PAL/NTSC)
|
||||
sbufWriteU8(dst, osdConfig()->video_system);
|
||||
sbufWriteU8(dst, osdConfig()->units);
|
||||
sbufWriteU8(dst, osdConfig()->rssi_alarm);
|
||||
sbufWriteU16(dst, currentBatteryProfile->capacity.warning);
|
||||
sbufWriteU16(dst, osdConfig()->time_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->alt_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->dist_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->neg_alt_alarm);
|
||||
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
|
||||
sbufWriteU16(dst, osdLayoutsConfig()->item_pos[0][i]);
|
||||
}
|
||||
#else
|
||||
sbufWriteU8(dst, OSD_DRIVER_NONE); // OSD not supported
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSP_3D:
|
||||
sbufWriteU16(dst, reversibleMotorsConfig()->deadband_low);
|
||||
sbufWriteU16(dst, reversibleMotorsConfig()->deadband_high);
|
||||
|
@ -1356,6 +1400,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
|
||||
break;
|
||||
|
||||
case MSP_POSITION_ESTIMATION_CONFIG:
|
||||
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_z_baro_p * 100); // inav_w_z_baro_p float as value * 100
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_z_gps_p * 100); // 2 inav_w_z_gps_p float as value * 100
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_z_gps_v * 100); // 2 inav_w_z_gps_v float as value * 100
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_xy_gps_p * 100); // 2 inav_w_xy_gps_p float as value * 100
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_xy_gps_v * 100); // 2 inav_w_xy_gps_v float as value * 100
|
||||
sbufWriteU8(dst, gpsConfigMutable()->gpsMinSats); // 1
|
||||
sbufWriteU8(dst, 1); // 1 inav_use_gps_velned ON/OFF
|
||||
|
||||
break;
|
||||
|
||||
case MSP_REBOOT:
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
if (mspPostProcessFn) {
|
||||
|
@ -2053,8 +2109,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SET_SERVO_CONFIG:
|
||||
if (dataSize != 8) {
|
||||
case MSP_SET_SERVO_CONFIGURATION:
|
||||
if (dataSize != (1 + 14)) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
tmp_u8 = sbufReadU8(src);
|
||||
|
@ -2065,10 +2121,28 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
servoParamsMutable(tmp_u8)->max = sbufReadU16(src);
|
||||
servoParamsMutable(tmp_u8)->middle = sbufReadU16(src);
|
||||
servoParamsMutable(tmp_u8)->rate = sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
sbufReadU8(src); // used to be forwardFromChannel, ignored
|
||||
sbufReadU32(src); // used to be reversedSources
|
||||
servoComputeScalingFactors(tmp_u8);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_SERVO_MIX_RULE:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize == 9) && (tmp_u8 < MAX_SERVO_RULES)) {
|
||||
customServoMixersMutable(tmp_u8)->targetChannel = sbufReadU8(src);
|
||||
customServoMixersMutable(tmp_u8)->inputSource = sbufReadU8(src);
|
||||
customServoMixersMutable(tmp_u8)->rate = sbufReadU16(src);
|
||||
customServoMixersMutable(tmp_u8)->speed = sbufReadU8(src);
|
||||
sbufReadU16(src); //Read 2bytes for min/max and ignore it
|
||||
sbufReadU8(src); //Read 1 byte for `box` and ignore it
|
||||
loadCustomServoMixer();
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_INAV_SET_SERVO_MIXER:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize == 7) && (tmp_u8 < MAX_SERVO_RULES)) {
|
||||
|
@ -2387,6 +2461,19 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP_SET_POSITION_ESTIMATION_CONFIG:
|
||||
if (dataSize == 12) {
|
||||
positionEstimationConfigMutable()->w_z_baro_p = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
positionEstimationConfigMutable()->w_z_gps_p = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
positionEstimationConfigMutable()->w_z_gps_v = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
positionEstimationConfigMutable()->w_xy_gps_p = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
positionEstimationConfigMutable()->w_xy_gps_v = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
gpsConfigMutable()->gpsMinSats = constrain(sbufReadU8(src), 5, 10);
|
||||
sbufReadU8(src); // was positionEstimationConfigMutable()->use_gps_velned
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP_RESET_CONF:
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
suspendRxSignal();
|
||||
|
@ -2445,6 +2532,36 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
#endif
|
||||
|
||||
#ifdef USE_OSD
|
||||
case MSP_SET_OSD_CONFIG:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
// set all the other settings
|
||||
if ((int8_t)tmp_u8 == -1) {
|
||||
if (dataSize >= 10) {
|
||||
osdConfigMutable()->video_system = sbufReadU8(src);
|
||||
osdConfigMutable()->units = sbufReadU8(src);
|
||||
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
||||
currentBatteryProfileMutable->capacity.warning = sbufReadU16(src);
|
||||
osdConfigMutable()->time_alarm = sbufReadU16(src);
|
||||
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
||||
// Won't be read if they weren't provided
|
||||
sbufReadU16Safe(&osdConfigMutable()->dist_alarm, src);
|
||||
sbufReadU16Safe(&osdConfigMutable()->neg_alt_alarm, src);
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
} else {
|
||||
// set a position setting
|
||||
if ((dataSize >= 3) && (tmp_u8 < OSD_ITEM_COUNT)) // tmp_u8 == addr
|
||||
osdLayoutsConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src);
|
||||
else
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
// Either a element position change or a units change needs
|
||||
// a full redraw, since an element can change size significantly
|
||||
// and the old position or the now unused space due to the
|
||||
// size change need to be erased.
|
||||
osdStartFullRedraw();
|
||||
break;
|
||||
|
||||
case MSP_OSD_CHAR_WRITE:
|
||||
if (dataSize >= 55) {
|
||||
osdCharacter_t chr;
|
||||
|
|
|
@ -213,7 +213,7 @@ void initActiveBoxIds(void)
|
|||
ADD_ACTIVE_BOX(BOXFPVANGLEMIX);
|
||||
}
|
||||
|
||||
bool navReadyAltControl = sensors(SENSOR_BARO);
|
||||
bool navReadyAltControl = getHwBarometerStatus() != HW_SENSOR_NONE;
|
||||
#ifdef USE_GPS
|
||||
navReadyAltControl = navReadyAltControl || (feature(FEATURE_GPS) && (STATE(AIRPLANE) || positionEstimationConfig()->use_gps_no_baro));
|
||||
|
||||
|
|
|
@ -110,6 +110,9 @@
|
|||
#define MSP_CALIBRATION_DATA 14
|
||||
#define MSP_SET_CALIBRATION_DATA 15
|
||||
|
||||
#define MSP_POSITION_ESTIMATION_CONFIG 16
|
||||
#define MSP_SET_POSITION_ESTIMATION_CONFIG 17
|
||||
|
||||
#define MSP_WP_MISSION_LOAD 18 // Load mission from NVRAM
|
||||
#define MSP_WP_MISSION_SAVE 19 // Save mission to NVRAM
|
||||
#define MSP_WP_GETINFO 20
|
||||
|
@ -186,6 +189,9 @@
|
|||
#define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
|
||||
#define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
|
||||
|
||||
#define MSP_OSD_CONFIG 84 //out message Get osd settings - betaflight
|
||||
#define MSP_SET_OSD_CONFIG 85 //in message Set osd settings - betaflight
|
||||
|
||||
#define MSP_OSD_CHAR_READ 86 //out message Get osd settings - betaflight
|
||||
#define MSP_OSD_CHAR_WRITE 87 //in message Set osd settings - betaflight
|
||||
|
||||
|
@ -198,7 +204,6 @@
|
|||
|
||||
#define MSP_FILTER_CONFIG 92
|
||||
#define MSP_SET_FILTER_CONFIG 93
|
||||
|
||||
#define MSP_PID_ADVANCED 94
|
||||
#define MSP_SET_PID_ADVANCED 95
|
||||
|
||||
|
@ -239,10 +244,11 @@
|
|||
#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
|
||||
#define MSP_ACTIVEBOXES 113 //out message Active box flags (full width, more than 32 bits)
|
||||
#define MSP_MISC 114 //out message powermeter trig
|
||||
#define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI
|
||||
#define MSP_BOXNAMES 116 //out message the aux switch names
|
||||
#define MSP_PIDNAMES 117 //out message the PID names
|
||||
#define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold
|
||||
#define MSP_BOXIDS 119 //out message get the permanent IDs associated to BOXes
|
||||
#define MSP_SERVO_CONFIGURATIONS 120 //out message All servo configurations.
|
||||
#define MSP_NAV_STATUS 121 //out message Returns navigation status
|
||||
#define MSP_NAV_CONFIG 122 //out message Returns navigation parameters
|
||||
#define MSP_3D 124 //out message Settings needed for reversible ESCs
|
||||
|
@ -262,6 +268,7 @@
|
|||
#define MSP_SET_WP 209 //in message sets a given WP (WP#,lat, lon, alt, flags)
|
||||
#define MSP_SELECT_SETTING 210 //in message Select Setting Number (0-2)
|
||||
#define MSP_SET_HEAD 211 //in message define a new heading hold direction
|
||||
#define MSP_SET_SERVO_CONFIGURATION 212 //in message Servo settings
|
||||
#define MSP_SET_MOTOR 214 //in message PropBalance function
|
||||
#define MSP_SET_NAV_CONFIG 215 //in message Sets nav config parameters - write to the eeprom
|
||||
#define MSP_SET_3D 217 //in message Settings needed for reversible ESCs
|
||||
|
@ -288,6 +295,8 @@
|
|||
#define MSP_GPSSTATISTICS 166 //out message get GPS debugging data
|
||||
#define MSP_ACC_TRIM 240 //out message get acc angle trim values
|
||||
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
|
||||
#define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
|
||||
#define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
|
||||
#define MSP_SET_PASSTHROUGH 245 //in message Sets up passthrough to different peripherals (4way interface, uart, etc...)
|
||||
#define MSP_RTC 246 //out message Gets the RTC clock (returns: secs(i32) millis(u16) - (0,0) if time is not known)
|
||||
#define MSP_SET_RTC 247 //in message Sets the RTC clock (args: secs(i32) millis(u16))
|
||||
|
|
|
@ -32,3 +32,4 @@
|
|||
// radar commands
|
||||
#define MSP2_COMMON_SET_RADAR_POS 0x100B //SET radar position information
|
||||
#define MSP2_COMMON_SET_RADAR_ITD 0x100C //SET radar information to display
|
||||
|
||||
|
|
|
@ -108,5 +108,3 @@
|
|||
#define MSP2_INAV_CUSTOM_OSD_ELEMENTS 0x2100
|
||||
#define MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS 0x2101
|
||||
|
||||
#define MSP2_INAV_SERVO_CONFIG 0x2200
|
||||
#define MSP2_INAV_SET_SERVO_CONFIG 0x2201
|
1
src/main/target/TAKERF722SE/CMakeLists.txt
Normal file
1
src/main/target/TAKERF722SE/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f722xe(TAKERF722SE)
|
48
src/main/target/TAKERF722SE/target.c
Normal file
48
src/main/target/TAKERF722SE/target.c
Normal file
|
@ -0,0 +1,48 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* INAV 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.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0),
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
||||
|
186
src/main/target/TAKERF722SE/target.h
Normal file
186
src/main/target/TAKERF722SE/target.h
Normal file
|
@ -0,0 +1,186 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "GEPR"
|
||||
|
||||
#define USBD_PRODUCT_STRING "TAKERF722SE"
|
||||
|
||||
#define LED0 PC14
|
||||
|
||||
|
||||
// *************** BEEPER ************************
|
||||
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA8
|
||||
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PA0
|
||||
#define UART4_RX_PIN PA1
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
|
||||
// *************** SPI Bus **********************
|
||||
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PB2
|
||||
#define SPI3_SCK_AF GPIO_AF6_SPI3
|
||||
#define SPI3_MISO_AF GPIO_AF6_SPI3
|
||||
#define SPI3_MOSI_AF GPIO_AF7_SPI3
|
||||
|
||||
|
||||
// *************** Gyro & ACC **********************
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
#define IMU_ICM42605_ALIGN CW0_DEG
|
||||
#define ICM42605_CS_PIN PA4
|
||||
#define ICM42605_SPI_BUS BUS_SPI1
|
||||
|
||||
// *************** I2C/Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
|
||||
//***************************************************
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** FLASH **************************
|
||||
|
||||
#define USE_FLASHFS
|
||||
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_CS_PIN PA15
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
// *************** OSD *****************************
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// *************** ADC *****************************
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_CHANNEL_1_PIN PC3
|
||||
#define ADC_CHANNEL_2_PIN PC0
|
||||
#define ADC_CHANNEL_3_PIN PC2
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
|
||||
|
||||
|
||||
|
||||
|
||||
//**************************************************
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
Loading…
Add table
Add a link
Reference in a new issue