1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 17:55:28 +03:00

Merge pull request #9432 from iNavFlight/release_7.0.0

Release 7.0.0
This commit is contained in:
Paweł Spychalski 2023-12-06 15:36:20 +01:00 committed by GitHub
commit 108aa4b10a
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
143 changed files with 2774 additions and 246 deletions

View file

@ -2,7 +2,10 @@
"files.associations": {
"chrono": "c",
"cmath": "c",
"ranges": "c"
"ranges": "c",
"platform.h": "c",
"timer.h": "c",
"bus.h": "c"
},
"editor.tabSize": 4,
"editor.insertSpaces": true,

View file

@ -5058,7 +5058,7 @@ Selection of pitot hardware.
| Default | Min | Max |
| --- | --- | --- |
| VIRTUAL | | |
| NONE | | |
---

View file

@ -462,9 +462,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, packSensorStatus());
sbufWriteU16(dst, averageSystemLoadPercent);
sbufWriteU8(dst, (getConfigBatteryProfile() << 4) | getConfigProfile());
sbufWriteU8(dst, getConfigMixerProfile());
sbufWriteU32(dst, armingFlags);
sbufWriteData(dst, &mspBoxModeFlags, sizeof(mspBoxModeFlags));
sbufWriteU8(dst, getConfigMixerProfile());
}
break;
@ -2581,6 +2581,29 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
if (sbufBytesRemaining(src) > 0) {
vtxSettingsConfigMutable()->lowPowerDisarm = sbufReadU8(src);
}
// //////////////////////////////////////////////////////////
// this code is taken from BF, it's hack for HDZERO VTX MSP frame
// API version 1.42 - this parameter kept separate since clients may already be supplying
if (sbufBytesRemaining(src) >= 2) {
sbufReadU16(src); //skip pitModeFreq
}
// API version 1.42 - extensions for non-encoded versions of the band, channel or frequency
if (sbufBytesRemaining(src) >= 4) {
uint8_t newBand = sbufReadU8(src);
const uint8_t newChannel = sbufReadU8(src);
vtxSettingsConfigMutable()->band = newBand;
vtxSettingsConfigMutable()->channel = newChannel;
}
/* if (sbufBytesRemaining(src) >= 4) {
sbufRead8(src); // freq_l
sbufRead8(src); // freq_h
sbufRead8(src); // band count
sbufRead8(src); // channel count
}*/
// //////////////////////////////////////////////////////////
}
}
}

View file

@ -119,8 +119,7 @@ throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e
value = rcCommand[THROTTLE];
}
const uint16_t mid_throttle_deadband = rcControlsConfig()->mid_throttle_deadband;
bool midThrottle = value > (PWM_RANGE_MIDDLE - mid_throttle_deadband) && value < (PWM_RANGE_MIDDLE + mid_throttle_deadband);
bool midThrottle = value > (reversibleMotorsConfig()->deadband_low) && value < (reversibleMotorsConfig()->deadband_high);
if ((feature(FEATURE_REVERSIBLE_MOTORS) && midThrottle) || (!feature(FEATURE_REVERSIBLE_MOTORS) && (value < rxConfig()->mincheck))) {
return THROTTLE_LOW;
}

View file

@ -588,7 +588,7 @@ groups:
members:
- name: pitot_hardware
description: "Selection of pitot hardware."
default_value: "VIRTUAL"
default_value: "NONE"
table: pitot_hardware
- name: pitot_lpf_milli_hz
min: 0

View file

@ -1042,12 +1042,15 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread)
gpsState.autoConfigStep = 0;
ubx_capabilities.supported = ubx_capabilities.enabledGnss = ubx_capabilities.defaultGnss = 0;
// M7 and earlier will never get pass this step, so skip it (#9440).
// UBLOX documents that this is M8N and later
if (gpsState.hwVersion > UBX_HW_VERSION_UBLOX7) {
do {
pollGnssCapabilities();
gpsState.autoConfigStep++;
ptWaitTimeout((ubx_capabilities.capMaxGnss != 0), GPS_CFG_CMD_TIMEOUT_MS);
} while (gpsState.autoConfigStep < GPS_VERSION_RETRY_TIMES && ubx_capabilities.capMaxGnss == 0);
}
// Configure GPS module if enabled
if (gpsState.gpsConfig->autoConfig) {
// Configure GPS

View file

@ -154,6 +154,7 @@
#define OSD_MIN_FONT_VERSION 3
static timeMs_t linearDescentMessageMs = 0;
static timeMs_t notify_settings_saved = 0;
static bool savingSettings = false;
@ -1000,6 +1001,9 @@ static const char * divertingToSafehomeMessage(void)
static const char * navigationStateMessage(void)
{
if (!posControl.rthState.rthLinearDescentActive && linearDescentMessageMs != 0)
linearDescentMessageMs = 0;
switch (NAV_Status.state) {
case MW_NAV_STATE_NONE:
break;
@ -1011,6 +1015,12 @@ static const char * navigationStateMessage(void)
if (posControl.flags.rthTrackbackActive) {
return OSD_MESSAGE_STR(OSD_MSG_RTH_TRACKBACK);
} else {
if (posControl.rthState.rthLinearDescentActive && (linearDescentMessageMs == 0 || linearDescentMessageMs > millis())) {
if (linearDescentMessageMs == 0)
linearDescentMessageMs = millis() + 5000; // Show message for 5 seconds.
return OSD_MESSAGE_STR(OSD_MSG_RTH_LINEAR_DESCENT);
} else
return OSD_MESSAGE_STR(OSD_MSG_HEADING_HOME);
}
case MW_NAV_STATE_HOLD_INFINIT:
@ -1052,6 +1062,7 @@ static const char * navigationStateMessage(void)
// Not used
break;
}
return NULL;
}

View file

@ -93,6 +93,7 @@
#define OSD_MSG_RTH_CLIMB "ADJUSTING RTH ALTITUDE"
#define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING"
#define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME"
#define OSD_MSG_RTH_LINEAR_DESCENT "BEGIN LINEAR DESCENT"
#define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION"
#define OSD_MSG_WP_LANDED "WP END>LANDED"
#define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT"

View file

@ -1227,6 +1227,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
{
UNUSED(previousState);
if (navConfig()->general.flags.rth_use_linear_descent && posControl.rthState.rthLinearDescentActive)
posControl.rthState.rthLinearDescentActive = false;
if ((posControl.flags.estHeadingStatus == EST_NONE) || (posControl.flags.estAltStatus == EST_NONE) || !STATE(GPS_FIX_HOME)) {
// Heading sensor, altitude sensor and HOME fix are mandatory for RTH. If not satisfied - switch to emergency landing
// Relevant to failsafe forced RTH only. Switched RTH blocked in selectNavEventFromBoxModeInput if sensors unavailable.
@ -1432,6 +1435,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio
if (homeDistance <= METERS_TO_CENTIMETERS(navConfig()->general.rth_linear_descent_start_distance)) {
posControl.rthState.rthFinalAltitude = posControl.rthState.homePosition.pos.z + navConfig()->general.rth_home_altitude;
posControl.rthState.rthLinearDescentActive = true;
}
}
@ -1442,6 +1446,10 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio
if (isWaypointReached(tmpHomePos, 0)) {
// Successfully reached position target - update XYZ-position
setDesiredPosition(tmpHomePos, posControl.rthState.homePosition.heading, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING);
if (navConfig()->general.flags.rth_use_linear_descent && posControl.rthState.rthLinearDescentActive)
posControl.rthState.rthLinearDescentActive = false;
return NAV_FSM_EVENT_SUCCESS; // NAV_STATE_RTH_HOVER_PRIOR_TO_LANDING
} else {
setDesiredPosition(tmpHomePos, 0, NAV_POS_UPDATE_Z | NAV_POS_UPDATE_XY);
@ -4053,7 +4061,8 @@ bool navigationPositionEstimateIsHealthy(void)
navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass)
{
const bool navBoxModesEnabled = IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD) || (STATE(FIXED_WING_LEGACY) && IS_RC_MODE_ACTIVE(BOXNAVALTHOLD)) || (STATE(FIXED_WING_LEGACY) && (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) || IS_RC_MODE_ACTIVE(BOXNAVCRUISE)));
const bool navBoxModesEnabled = IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) ||
IS_RC_MODE_ACTIVE(BOXNAVCRUISE) || IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD) || (STATE(FIXED_WING_LEGACY) && IS_RC_MODE_ACTIVE(BOXNAVALTHOLD));
if (usedBypass) {
*usedBypass = false;

View file

@ -518,8 +518,8 @@ void applyFixedWingPositionController(timeUs_t currentTimeUs)
// POSITION_TARGET_UPDATE_RATE_HZ should be chosen keeping in mind that position target shouldn't be reached until next pos update occurs
// FIXME: verify the above
calculateVirtualPositionTarget_FW(HZ2S(MIN_POSITION_UPDATE_RATE_HZ) * 2);
updatePositionHeadingController_FW(currentTimeUs, deltaMicrosPositionUpdate);
needToCalculateCircularLoiter = false;
}
else {
// Position update has not occurred in time (first iteration or glitch), reset altitude controller

View file

@ -350,6 +350,7 @@ typedef struct {
float rthInitialDistance; // Distance when starting flight home
fpVector3_t homeTmpWaypoint; // Temporary storage for home target
fpVector3_t originalHomePosition; // the original rth home - save it, since it could be replaced by safehome or HOME_RESET
bool rthLinearDescentActive; // Activation status of Linear Descent
} rthState_t;
typedef enum {

View file

@ -32,12 +32,13 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED | TIM_USE_ANY, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port)
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S3_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S4_IN
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S5_IN
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S6_IN
//Airbot F4 don't have those outputs, they exist only in the original Revo
// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port)
// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN
// DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S3_IN
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S4_IN
// DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S5_IN
// DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S6_IN
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -23,11 +23,10 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7
DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, 0, 1), // PWM4 - PA14 RC4 - DMA2_ST2
DEF_TIM(TIM1, CH3, PB15, TIM_USE_PWM | TIM_USE_LED, 0, 0), // PWM5 - PA15 RC5 - DMA2_ST6
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1
// DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5
// DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7
// DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, 0, 1), // PWM4 - PA14 RC4 - DMA2_ST2
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2
@ -36,6 +35,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7
DEF_TIM(TIM1, CH3, PB15, TIM_USE_LED, 0, 0), // PWM5 - PA15 RC5 - DMA2_ST6
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -23,7 +23,6 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM1 - DMA2_ST2
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM2 - DMA1_ST5
DEF_TIM(TIM8, CH2N, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM3 - DMA2_ST3
@ -36,6 +35,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM10 - DMA2_ST6
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM11 - DMA1_ST7
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM12 - DMA_NONE
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 1), // PPM - DMA2_ST1
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -23,12 +23,12 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN
// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN
// DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN
// DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN
// DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S10_OUT 16
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT 12

View file

@ -23,12 +23,13 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_IN DMA2_ST7
// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_IN DMA2_ST7
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST0
@ -40,6 +41,8 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7_OUT DMA1_ST2
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S9_OUT DMA1_ST4
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -26,12 +26,12 @@
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL
timerHardware_t timerHardware[] = {
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S6_IN DMA2_ST7
// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
// DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
// DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
// DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S6_IN DMA2_ST7
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST1

View file

@ -28,7 +28,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU65
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH2, PA10, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM2, CH2, PA10, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2

View file

@ -25,7 +25,7 @@
#include "drivers/bus.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S2

View file

@ -27,7 +27,7 @@
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S2

View file

@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS,
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM
// DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(2, 2, 7)
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(2, 3, 7)

View file

@ -37,7 +37,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS,
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM, RX1
// DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM, RX1
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1, 4, 5)
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1, 5, 4)

View file

@ -0,0 +1 @@
target_stm32f405xg(ATOMRCF405NAVI_DELUX)

View file

@ -0,0 +1,37 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
#include "io/serial.h"
void targetConfiguration(void)
{
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].msp_baudrateIndex = BAUD_115200;
pinioBoxConfigMutable()->permanentId[0] = BOXARM;
}

View file

@ -0,0 +1,56 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S9
DEF_TIM(TIM8, CH2N, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // S10
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S11
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED_STRIP
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,189 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "AT4D"
#define USBD_PRODUCT_STRING "AtomRCF405NAVI_DELUX"
#define LED0 PA13
#define LED1 PA14
#define BEEPER PB2
#define BEEPER_INVERTED
/*
* SPI defines
*/
#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 PC2
#define SPI2_MOSI_PIN PC3
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
/*
* I2C defines
*/
#define USE_I2C
#define DEFAULT_I2C_BUS BUS_I2C1
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
//ICM42688-P
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_CS_PIN PA4
#define ICM42605_SPI_BUS BUS_SPI1
/*
* Magnetometer
*/
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_ALL
/*
* Barometer
*/
#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_ALL
/*
* Serial ports
*/
#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_UART4
#define USE_UART5
#define USE_UART6
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PC10
#define UART3_RX_PIN PC11
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define SERIAL_PORT_COUNT 7
/*
* ADC
*/
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1
#define ADC_CHANNEL_3_PIN PC4
#define ADC_CHANNEL_4_PIN PC5
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4
#define CURRENT_METER_SCALE 128
/*
* OSD
*/
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
/*
* SD Card
*/
#define USE_SDCARD
#define USE_SDCARD_SPI
#define SDCARD_SPI_BUS BUS_SPI3
#define SDCARD_CS_PIN PC14
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
/*
* LED Strip
*/
#define USE_LED_STRIP
#define WS2811_PIN PA8
/*
* Other configs
*/
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT )
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_OPFLOW
#define USE_OPFLOW_MSP
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define MAX_PWM_OUTPUT_PORTS 11
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC15
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED

View file

@ -33,7 +33,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 1), // S7
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // CAM CONTROL
};

View file

@ -24,7 +24,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 - DMAR: DMA2_ST5
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 -

View file

@ -24,7 +24,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM
// Motors
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7

View file

@ -25,7 +25,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1 D(1, 4, 5)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2 D(2, 3, 7)

View file

@ -35,7 +35,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), //ST1 pad -softserial_tx1
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 Pad -PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 Pad -PPM
};

View file

@ -23,7 +23,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT - DMA1_ST2
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - DMA1_ST4

View file

@ -21,8 +21,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0),
// DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0),
#if defined(CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3)
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
@ -39,6 +38,7 @@
DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0),
#endif
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -24,14 +24,14 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S2_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S3_IN
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S4_IN
DEF_TIM(TIM2, CH1, PA15, TIM_USE_PWM, 0, 0), // S5_IN
DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM, 0, 0), // S6_IN
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // S7_IN
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // S8_IN
// DEF_TIM(TIM1, CH3, PA10, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
// DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S2_IN
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S3_IN
// DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S4_IN
// DEF_TIM(TIM2, CH1, PA15, TIM_USE_PWM, 0, 0), // S5_IN
// DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM, 0, 0), // S6_IN
// DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // S7_IN
// DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // S8_IN
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT

View file

@ -0,0 +1 @@
target_stm32f405xg(DAKEFPVF405)

View file

@ -0,0 +1,31 @@
/*
* This file is part of INAV.
*
* 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 <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "io/serial.h"
#include "rx/rx.h"
#include "fc/fc_msp_box.h"
#include "io/piniobox.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}

View file

@ -0,0 +1,36 @@
/*
* This file is part of INAV.
*
* 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 <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,168 @@
/*
* This file is part of INAV.
*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "DAK4"
#define USBD_PRODUCT_STRING "DAKEFPV F405"
#define LED0 PC14
#define LED1 PC15
#define BEEPER PC3
#define BEEPER_INVERTED
// Buses
#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 PB5
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define DEFAULT_I2C_BUS BUS_I2C1
// Gyro
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW90_DEG
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_BUS BUS_SPI1
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW90_DEG
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW90_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN PA4
//Baro
#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS BUS_SPI2
#define BMP280_CS_PIN PC13
#define USE_BARO_DPS310
#define DPS310_SPI_BUS BUS_SPI2
#define DPS310_CS_PIN PC13
// M25P256 flash
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_SPI_BUS BUS_SPI3
#define M25P16_CS_PIN PA15
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// Serial ports
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
// Mag
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_ALL
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
// ADC
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC2
#define ADC_CHANNEL_3_PIN PC0
#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_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY )
#define USE_LED_STRIP
#define WS2811_PIN PB3
#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 0xffff
#define USE_DSHOT
#define USE_ESC_SENSOR
#define MAX_PWM_OUTPUT_PORTS 6
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC5
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED

View file

@ -0,0 +1 @@
target_stm32f722xe(DAKEFPVF722)

View file

@ -0,0 +1,28 @@
/*
* This file is part of INAV.
*
* 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 <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "io/serial.h"
#include "rx/rx.h"
void targetConfiguration(void)
{
}

View file

@ -0,0 +1,36 @@
/*
* This file is part of INAV.
*
* 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 <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0),
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,150 @@
/*
* This file is part of INAV.
*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "DAK7"
#define USBD_PRODUCT_STRING "DAKEFPV F722"
#define LED0 PC14
#define LED1 PC15
#define BEEPER PC3
#define BEEPER_INVERTED
// Buses
#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 PB5
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define DEFAULT_I2C_BUS BUS_I2C1
// Gyro
#define USE_IMU_MPU6500
#define IMU_MPU6500_ALIGN CW90_DEG
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_BUS BUS_SPI1
//Baro
#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS BUS_SPI2
#define BMP280_CS_PIN PA13
// M25P256 flash
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_SPI_BUS BUS_SPI3
#define M25P16_CS_PIN PA15
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// Serial ports
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
// Mag
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_ALL
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
// ADC
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC2
#define ADC_CHANNEL_3_PIN PC0
#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_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY )
#define USE_LED_STRIP
#define WS2811_PIN PB3
#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 0xffff
#define USE_DSHOT
#define USE_ESC_SENSOR
#define MAX_PWM_OUTPUT_PORTS 6

View file

@ -22,7 +22,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 (1,7)
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 (2,2)

View file

@ -28,7 +28,7 @@
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM ,0, 0),
// DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM ,0, 0),
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO,0,0), //S1 DMA2_ST2 T8CH1
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO,0,0), //S2 DMA2_ST3 T8CH2

View file

@ -6,14 +6,14 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH4, PC9, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // S1_IN
DEF_TIM(TIM3, CH3, PC8, TIM_USE_PWM, 0, 0), // S2_IN
DEF_TIM(TIM3, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
DEF_TIM(TIM3, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN
DEF_TIM(TIM4, CH4, PD15, TIM_USE_PWM, 0, 0), // S5_IN
DEF_TIM(TIM4, CH3, PD14, TIM_USE_PWM, 0, 0), // S6_IN
DEF_TIM(TIM4, CH2, PD13, TIM_USE_PWM, 0, 0), // S7_IN
DEF_TIM(TIM4, CH1, PD12, TIM_USE_PWM, 0, 0), // S8_IN
// DEF_TIM(TIM3, CH4, PC9, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // S1_IN
// DEF_TIM(TIM3, CH3, PC8, TIM_USE_PWM, 0, 0), // S2_IN
// DEF_TIM(TIM3, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
// DEF_TIM(TIM3, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN
// DEF_TIM(TIM4, CH4, PD15, TIM_USE_PWM, 0, 0), // S5_IN
// DEF_TIM(TIM4, CH3, PD14, TIM_USE_PWM, 0, 0), // S6_IN
// DEF_TIM(TIM4, CH2, PD13, TIM_USE_PWM, 0, 0), // S7_IN
// DEF_TIM(TIM4, CH1, PD12, TIM_USE_PWM, 0, 0), // S8_IN
DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT
DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT

View file

@ -33,11 +33,11 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0),
DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 0),
#ifdef WINGFC
DEF_TIM(TIM2, CH4, PB11, TIM_USE_PPM, 0, 0), // UART3 RX
#else
DEF_TIM(TIM2, CH3, PB10, TIM_USE_PPM, 0, 0), // UART3 TX
#endif
// #ifdef WINGFC
// DEF_TIM(TIM2, CH4, PB11, TIM_USE_PPM, 0, 0), // UART3 RX
// #else
// DEF_TIM(TIM2, CH3, PB10, TIM_USE_PPM, 0, 0), // UART3 TX
// #endif
};

View file

@ -27,7 +27,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S2_OUT - DMA1_ST2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 1, 1 ), // S3_OUT - DMA1_ST6
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S4_OUT - DMA1_ST1
DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED - DMA1_ST3
};

View file

@ -44,7 +44,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6000, DEVHW_MPU6000, IMU_2_SPI_BUS, IMU_
BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6500, DEVHW_MPU6500, IMU_2_SPI_BUS, IMU_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
// Motor output 1: use different set of timers for MC and FW
//DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM _USE_SERVO, 1, 0), // S1_OUT D(1,7)

View file

@ -23,12 +23,12 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0 ),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0 ),
DEF_TIM(TIM2, CH3, PB10, TIM_USE_PWM, 0, 0 ),
DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0, 0 ),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM, 0, 0 ),
// DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0 ),
// DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0 ),
// DEF_TIM(TIM2, CH3, PB10, TIM_USE_PWM, 0, 0 ),
// DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0, 0 ),
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM, 0, 0 ),
DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0 ),
DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0 ),

View file

@ -0,0 +1 @@
target_stm32f405xg(FLASHHOBBYF405)

View file

@ -0,0 +1,43 @@
/*
* 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.
*
* 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 <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(TIM5, CH4, PA3, TIM_USE_PPM, 0, 1),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S7
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 1),//WS2812B
// DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // "C.C"
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,164 @@
/*
* 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.
*
* 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 <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "FHRCF405"
#define USBD_PRODUCT_STRING "FLASHHOBBYF405"
#define LED0 PC14
#define BEEPER PB2
#define BEEPER_INVERTED
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW0_DEG
#define MPU6000_CS_PIN SPI1_NSS_PIN
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW0_DEG
#define BMI270_CS_PIN SPI1_NSS_PIN
#define BMI270_SPI_BUS BUS_SPI1
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW0_DEG
#define ICM42605_CS_PIN SPI1_NSS_PIN
#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 DEFAULT_I2C_BUS BUS_I2C1
#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_ALL
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_ALL
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
// *************** OSD *****************************
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN SPI2_NSS_PIN
// *************** FLASH **************************
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define M25P16_CS_PIN SPI3_NSS_PIN
#define M25P16_SPI_BUS BUS_SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** UART *****************************
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN NONE
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
// *************** PINIO ************************
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC13
// *************** LEDSTRIP ************************
#define USE_LED_STRIP
#define WS2811_PIN PA8
#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

View file

@ -0,0 +1 @@
target_stm32f722xe(FLASHHOBBYF722)

View file

@ -0,0 +1,45 @@
/*
* 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.
*
* 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 <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(TIM5, CH4, PA3, TIM_USE_PPM, 0, 1),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S7
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 1),//WS2812B
// DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // "C.C"
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,162 @@
/*
* 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.
*
* 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 <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "FHRCF722"
#define USBD_PRODUCT_STRING "FLASHHOBBYF722"
#define LED0 PC14
#define BEEPER PC15
#define BEEPER_INVERTED
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW0_DEG
#define MPU6000_CS_PIN SPI1_NSS_PIN
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW0_DEG
#define BMI270_CS_PIN SPI1_NSS_PIN
#define BMI270_SPI_BUS BUS_SPI1
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW0_DEG
#define ICM42605_CS_PIN SPI1_NSS_PIN
#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 DEFAULT_I2C_BUS BUS_I2C1
#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_ALL
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_ALL
#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS
#define PITOT_I2C_BUS DEFAULT_I2C_BUS
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS
// *************** FLASH **************************
#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define M25P16_CS_PIN SPI3_NSS_PIN
#define M25P16_SPI_BUS BUS_SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** OSD *****************************
#define USE_SPI_DEVICE_2
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN SPI2_NSS_PIN
// *************** UART *****************************
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN NONE
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
// *************** PINIO ************************
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC13
// *************** LEDSTRIP ************************
#define USE_LED_STRIP
#define WS2811_PIN PA8
#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

View file

@ -34,7 +34,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), //2812LED D(1,5,3)
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1 @@
target_stm32f405xg(FLYWOOF405S_AIO SKIP_RELEASES)

View file

@ -0,0 +1,37 @@
/*
* This file is part of INAV.
*
* 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 <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), //2812LED D(1,5,3)
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,174 @@
/*
* This file is part of INAV.
*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "F4SA"
#define USBD_PRODUCT_STRING "FLYWOOF405S_AIO"
#define LED0 PC14 //Green
#define BEEPER PC13
#define BEEPER_INVERTED
// *************** SPI1 Gyro & ACC *******************
#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_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW270_DEG
#define BMI270_CS_PIN PB12
#define BMI270_SPI_BUS BUS_SPI1
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_CS_PIN PB12
#define ICM42605_SPI_BUS BUS_SPI1
#define USE_EXTI
#define GYRO_INT_EXTI PB13
#define USE_MPU_DATA_READY_SIGNAL
// *************** 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_MS5611
#define USE_BARO_BMP085
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_AK8963
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define PITOT_I2C_BUS BUS_I2C1
#define TEMPERATURE_I2C_BUS BUS_I2C1
// *************** SPI2 OSD ***************************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PB14//
// *************** Onboard flash ********************
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
#define M25P16_SPI_BUS BUS_SPI3
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** UART *****************************
#define USB_IO
#define USE_VCP
#define VBUS_SENSING_PIN PA8
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PA10
#define USE_UART2
#define UART2_TX_PIN PD5
#define UART2_RX_PIN PD6
#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 NONE
#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_USART3
// *************** 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 PC2
#define ADC_CHANNEL_3_PIN PC0
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// *************** LED2812 ************************
#define USE_LED_STRIP
#define WS2811_PIN PA9
// *************** OTHERS *************************
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
#define CURRENT_METER_SCALE 250
#define USE_DSHOT
#define USE_ESC_SENSOR
#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 0x0064
#define MAX_PWM_OUTPUT_PORTS 8

View file

@ -25,7 +25,7 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN
// DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN
#ifdef FLYWOOF411_V2
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 - D(2,1)
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - D(1,6)

View file

@ -22,7 +22,16 @@
#include "io/piniobox.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_mapping.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
// Make sure S1-S4 default to Motors
timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS;
timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS;
timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS;
}

View file

@ -30,13 +30,13 @@
#include "drivers/pinio.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6
// DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 , DMA1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 , DMA1_ST2
DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 2), // M3 , DMA2_ST2
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 , DMA1_ST2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 , DMA2_ST7
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M3 , DMA1_ST7
DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // M4 , DMA2_ST4
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 , DMA2_ST7
DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 2), // M5 , DMA2_ST2
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // M6 , DMA1_ST1
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // M7 , DMA1_ST4
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // M8 , DMA1_ST5

View file

@ -140,6 +140,10 @@
#define USE_BARO
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define BARO_I2C_BUS BUS_I2C1
#define USE_MAG

View file

@ -38,7 +38,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_2, DEVHW_MPU6000, GYRO_2_SPI_BUS, GYRO
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, GYRO_2_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS
// DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 - D(1,2)
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - D(1,4)

View file

@ -22,7 +22,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 (1,7)
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 (1,4)

View file

@ -29,7 +29,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS,
#endif
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
// DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 - D(2, 1, 6)
#if defined(FOXEERF722V2)

View file

@ -23,7 +23,7 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1_OUT - D(1, 6, 3)
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - D(1, 7, 5)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT - D(1, 2, 5)

View file

@ -24,12 +24,8 @@
#include "drivers/timer.h"
#include "drivers/timer_def.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0),
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1),
DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1),

View file

@ -27,7 +27,7 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0),

View file

@ -25,10 +25,8 @@
#include "drivers/timer.h"
#include "drivers/sensor.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0),

View file

@ -27,7 +27,7 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0),

View file

@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU600
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // S2
@ -41,9 +41,9 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH1, PB8, TIM_USE_LED, 0, 0), // LED STRIP(2,6)
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // PWM1
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // PWM2
DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PWM3
// DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // PWM1
// DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // PWM2
// DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PWM3
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -23,7 +23,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2

View file

@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2

View file

@ -47,8 +47,8 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 UP1-6 D(1, 3, 2)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0)
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2
DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2
// DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -24,7 +24,7 @@
#include "drivers/pinio.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0),
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0),
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0),

View file

@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6
BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_1_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// Motors
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D2_ST6

View file

@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6
BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_1_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0),

View file

@ -0,0 +1 @@
target_at32f43x_xGT7(IFLIGHT_BLITZ_ATF435)

View file

@ -0,0 +1,50 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TMR3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0,8), // S1
DEF_TIM(TMR3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0,9), // S2
DEF_TIM(TMR8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0,2), // S3
DEF_TIM(TMR8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0,0), // S4
DEF_TIM(TMR4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0,11), // S5
DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0,10), // S6
DEF_TIM(TMR2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0,5), //S7
DEF_TIM(TMR2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0,6), //S8
DEF_TIM(TMR1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,157 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute 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.
*
* This file 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 this program. If not, see http://www.gnu.org/licenses/.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "IAT4"
#define USBD_PRODUCT_STRING "iFlight BLITZ ATF435"
#define LED0 PC15
#define BEEPER PB2
#define BEEPER_INVERTED
// Buses
#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 PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
// #define USE_I2C_PULLUP
#define DEFAULT_I2C_BUS BUS_I2C1
// Gyro
// BMI270
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW0_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PA4
// Other sensors
#define USE_BARO
#define BARO_I2C_BUS DEFAULT_I2C_BUS
#define USE_BARO_ALL
#define USE_MAG
#define MAG_I2C_BUS DEFAULT_I2C_BUS
#define USE_MAG_ALL
// OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// Flash
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_SPI_BUS BUS_SPI3
#define M25P16_CS_PIN PA15
#define USE_FLASH_W25N01G
#define W25N01G_SPI_BUS BUS_SPI3
#define W25N01G_CS_PIN PA15
// UARTs
#define USE_VCP
// #define USB_DETECT_PIN PC5
// #define USE_USB_DETECT
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PC11
#define UART3_TX_PIN PC10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_CHANNEL5
#define ADC_CHANNEL_1_PIN PC2
#define ADC_CHANNEL_2_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD )
#define USE_LED_STRIP
#define WS2811_PIN PA8
#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 0xffff
#define TARGET_IO_PORTE BIT(2)
#define MAX_PWM_OUTPUT_PORTS 4
#define USE_DSHOT
#define USE_ESC_SENSOR

View file

@ -30,7 +30,7 @@
//BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH2, PB3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM2, CH2, PB3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S2

View file

@ -30,7 +30,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2

View file

@ -25,7 +25,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2

View file

@ -0,0 +1 @@
target_stm32f405xg(JHEMCUF405)

View file

@ -0,0 +1,39 @@
/*
* This file is part of INAV.
*
* 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 <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,3,2)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,0,2)
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 D(1,7,5)
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1,2,5)
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2,4,7)
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(2,7,7)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), // 2812LED D(1,5,3)
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,164 @@
/*
* This file is part of INAV.
*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "JH45"
#define USBD_PRODUCT_STRING "JHEMCUF405"
#define LED0 PC14 //Green
#define BEEPER PC13
#define BEEPER_INVERTED
// *************** SPI1 Gyro & ACC *******************
#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_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW90_DEG
#define MPU6000_CS_PIN PB12
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW90_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PB12
#define BMI270_EXTI_PIN GYRO_INT_EXTI
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW90_DEG
#define ICM42605_CS_PIN PB12
#define ICM42605_SPI_BUS BUS_SPI1
#define USE_EXTI
#define GYRO_INT_EXTI PB13
#define USE_MPU_DATA_READY_SIGNAL
// *************** 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_MS5611
#define USE_BARO_BMP085
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_AK8963
#define USE_MAG_AK8975
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C1
#define PITOT_I2C_BUS BUS_I2C1
#define TEMPERATURE_I2C_BUS BUS_I2C1
// *************** SPI2 OSD ***************************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PB14
// *************** Onboard flash ********************
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
#define M25P16_SPI_BUS BUS_SPI3
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** UART *****************************
#define USB_IO
#define USE_VCP
#define VBUS_SENSING_PIN PA8
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PA10
#define USE_UART2
#define UART2_TX_PIN PD5
#define UART2_RX_PIN PD6
#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_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define SERIAL_PORT_COUNT 6
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
// *************** 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 PC2
#define ADC_CHANNEL_3_PIN PC0
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// *************** LED2812 ************************
#define USE_LED_STRIP
#define WS2811_PIN PA9
// *************** OTHERS *************************
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
#define CURRENT_METER_SCALE 250
#define USE_DSHOT
#define USE_ESC_SENSOR
#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 0xffff
#define MAX_PWM_OUTPUT_PORTS 8

View file

@ -0,0 +1 @@
target_stm32f722xe(JHEMCUF722)

View file

@ -0,0 +1,28 @@
/*
* This file is part of INAV.
*
* 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 "fc/fc_msp_box.h"
#include "io/piniobox.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; // VTX power switch
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
}

View file

@ -0,0 +1,45 @@
/*
* This file is part of INAV.
*
* 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/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0 ), //PPM&SBUS
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 DMA1_S7_CH5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 - D(1,2)
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - D(1,4)
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 - D(1,6)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 - D(2,1)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 - D(2,4)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP(1,5)
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,182 @@
/*
* This file is part of INAV.
*
* 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/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "JHF7"
#define USBD_PRODUCT_STRING "JHEMCUF722"
#define LED0 PA15
#define USE_BEEPER
#define BEEPER PC15
#define BEEPER_INVERTED
// PINIO
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC14
#define PINIO2_PIN PB9
// UART
#define USB_IO
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 7
// Gyro & Acc
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
#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_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW90_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN PA4
#define ICM42605_EXTI_PIN PC3
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW90_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN PA4
#define BMI270_EXTI_PIN PC3
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW90_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PA4
#define MPU6000_EXTI_PIN PC3
// I2C (Baro & Mag)
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
// Baro
#define USE_BARO
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define BARO_I2C_BUS BUS_I2C1
// Mag
#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 USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
// Onboard Flash
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PB5
#define M25P16_SPI_BUS BUS_SPI3
#define M25P16_CS_PIN PC13
#define W25N01G_SPI_BUS BUS_SPI3
#define W25N01G_CS_PIN PC13
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_FLASH_W25N01G
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// OSD
#define USE_OSD
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// ADC
#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC2
#define ADC_CHANNEL_3_PIN PC0
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// LED
#define USE_LED_STRIP
#define WS2811_PIN PA8
// Optical Flow & Lidar
#define USE_RANGEFINDER
#define USE_RANGEFINDER_MSP
#define USE_OPFLOW
#define USE_OPFLOW_MSP
// Misc
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
#define USE_DSHOT
#define USE_ESC_SENSOR
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define SERIALRX_UART SERIAL_PORT_USART2
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define MAX_PWM_OUTPUT_PORTS 6
#define CURRENT_METER_SCALE 250
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

View file

@ -1,3 +1,4 @@
target_stm32f405xg(KAKUTEF4)
target_stm32f405xg(KAKUTEF4V2)
target_stm32f405xg(KAKUTEF4V23)
target_stm32f405xg(KAKUTEF4V24)

View file

@ -29,21 +29,21 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT - DMA1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT - DMA1_ST2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT - DMA1_ST6
#if !defined(KAKUTEF4V23)
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST1
#else
#if defined(KAKUTEF4V23) || defined(KAKUTEF4V24)
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST1
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA1_ST0
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT - DMA1_ST3
#else
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST1
#endif
#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23)
#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) || defined(KAKUTEF4V24)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2
#else
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA1_ST2

View file

@ -29,6 +29,9 @@
#elif defined(KAKUTEF4V23)
# define TARGET_BOARD_IDENTIFIER "KT23"
# define USBD_PRODUCT_STRING "KakuteF4-V2.3"
#elif defined(KAKUTEF4V24)
# define TARGET_BOARD_IDENTIFIER "KT24"
# define USBD_PRODUCT_STRING "KakuteF4-V2.4"
#else
# define TARGET_BOARD_IDENTIFIER "KTV1"
# define USBD_PRODUCT_STRING "KakuteF4-V1"
@ -37,7 +40,7 @@
#define LED0 PB5
#define LED1 PB4
#if !defined(KAKUTEF4V23)
#if defined(KAKUTEF4) || defined(KAKUTEF4V2)
# define LED2 PB6
#endif
@ -54,7 +57,7 @@
#define MPU6000_CS_PIN PC4
#define MPU6000_SPI_BUS BUS_SPI1
#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23)
#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) || defined(KAKUTEF4V24)
# define USE_I2C
# define USE_I2C_DEVICE_1
# define I2C1_SCL PB8 // SCL pad
@ -79,11 +82,12 @@
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PB14
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB3
#define M25P16_SPI_BUS BUS_SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USB_IO
#define USE_VCP
@ -105,7 +109,7 @@
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23)
#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) || defined(KAKUTEF4V24)
# define USE_UART4
# define UART4_RX_PIN PA1
# define UART4_TX_PIN PA0
@ -153,7 +157,7 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD)
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_BLACKBOX)
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART3

3
src/main/target/KAKUTEF7/target.c Executable file → Normal file
View file

@ -29,7 +29,6 @@
#include "drivers/bus.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 , DMA1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 , DMA1_ST2
@ -38,6 +37,8 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 , DMA2_ST7
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // M6 , DMA1_ST1
//DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 1), // PPM/M7, DMA2_ST6
DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0
};

View file

@ -38,7 +38,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2
// DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -88,6 +88,13 @@
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN PB2
// ICM42688
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN PB2
#define ICM42605_EXTI_PIN PA4
/*
* Blackbox Onboard Flash
*/

View file

@ -23,7 +23,7 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN
// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // PWM4
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 0), // PWM2

View file

@ -25,7 +25,7 @@
#include "drivers/bus.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
#ifdef MAMBAF405US_I2C
DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0

View file

@ -25,7 +25,7 @@
#include "drivers/bus.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
// DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT D(2, 4, 7)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT D(2, 7, 7)

Some files were not shown because too many files have changed in this diff Show more