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

Merge branch 'master' into sh_mixer_profile

This commit is contained in:
shota 2023-07-22 12:23:14 +09:00
commit 1273d862aa
34 changed files with 817 additions and 58 deletions

View file

@ -59,6 +59,9 @@ if(NOT MACOSX)
-Wno-error=maybe-uninitialized -Wno-error=maybe-uninitialized
-fsingle-precision-constant -fsingle-precision-constant
) )
if (CMAKE_COMPILER_IS_GNUCC AND NOT CMAKE_C_COMPILER_VERSION VERSION_LESS 12.0)
set(SITL_LINK_OPTIONS ${SITL_LINK_OPTIONS} "-Wl,--no-warn-rwx-segments")
endif()
else() else()
set(SITL_COMPILE_OPTIONS ${SITL_COMPILE_OPTIONS} set(SITL_COMPILE_OPTIONS ${SITL_COMPILE_OPTIONS}
) )

View file

@ -62,12 +62,14 @@ beeper list
giving: giving:
``` ```
Available: RUNTIME_CALIBRATION HW_FAILURE RX_LOST RX_LOST_LANDING DISARMING ARMING ARMING_GPS_FIX BAT_CRIT_LOW BAT_LOW GPS_STATUS RX_SET ACTION_SUCCESS ACTION_FAIL READY_BEEP MULTI_BEEPS DISARM_REPEAT ARMED SYSTEM_INIT ON_USB LAUNCH_MODE CAM_CONNECTION_OPEN CAM_CONNECTION_CLOSED ALL PREFERED Available: RUNTIME_CALIBRATION HW_FAILURE RX_LOST RX_LOST_LANDING DISARMING ARMING ARMING_GPS_FIX BAT_CRIT_LOW
BAT_LOW GPS_STATUS RX_SET ACTION_SUCCESS ACTION_FAIL READY_BEEP MULTI_BEEPS DISARM_REPEAT ARMED SYSTEM_INIT
ON_USB LAUNCH_MODE CAM_CONNECTION_OPEN CAM_CONNECTION_CLOSED ALL PREFERED
``` ```
The `beeper` command syntax follows that of the `feature` command; a minus (`-`) in front of a name disables that function. The `beeper` command syntax follows that of the `feature` command; a minus (`-`) in front of a name disables that function.
So to disable the beeper / buzzer when connected to USB (may enhance domestic harmony) So to disable the beeper / buzzer when powered by USB (may enhance domestic harmony):
``` ```
beeper -ON_USB beeper -ON_USB
@ -78,17 +80,39 @@ Now the `beeper` command will show:
``` ```
# beeper # beeper
Disabled: ON_USB Disabled: ON_USB
```
*Note: SYSTEM_INIT sequence is not affected by ON_USB setting and will still be played on USB connection. Disable both ON_USB and SYSTEM_INIT to disable buzzer completely when FC is powered from USB.*
*Note: ON_USB setting requires present and configured battery voltage metter.*
To disable all features use:
``` ```
beeper -ALL
```
To store current set to preferences use (preferences also require ```save```):
```
beeper PREFERED
```
To restore set from preferences use:
```
beeper -PREFERED
As with other CLI commands, the `save` command is needed to save the new settings. As with other CLI commands, the `save` command is needed to save the new settings.
## Types of buzzer supported ## Types of buzzer supported
The buzzers are enabled/disabled by simply enabling or disabling a GPIO output pin on the board. Most FCs require ACTIVE buzzers. Active buzzers are enabled/disabled by simply enabling or disabling a GPIO output pin on the board.
This means the buzzer must be able to generate its own tone simply by having power applied to it. This means the buzzer must be able to generate its own tone simply by having power applied to it.
Buzzers that need an analog or PWM signal do not work and will make clicking noises or no sound at all. Passive buzzers that need an analog or PWM signal do not work and will make clicking noises or no sound at all.
Passive buzzers are supported on FCs which are designed to work with passive buzzers only (so far there is no available, except rare cases like Matek F765-WSE where passive buzzer is preinstalled).
Examples of a known-working buzzers. Examples of a known-working buzzers.

Binary file not shown.

Before

Width:  |  Height:  |  Size: 773 KiB

After

Width:  |  Height:  |  Size: 774 KiB

Before After
Before After

View file

@ -0,0 +1,53 @@
# Introduction
While many of the instructions here are somewhat generic and will likely work for other projects, the goal of these instructions is to assist a non-developer INAV user to acquire firmware that includes a pull request so he can flash it on his supported fc.
Building the pull request manually or using custom/unofficial targets is not the focus of this document.
# Why should you test a pull request?
- You want to volunteer time and resources helping improving INAV for everyone by catching issues before they are introduced in the next release of INAV!
- You reported or are affected by a bug that has been addressed by this pull request and want to help test the fix
- You are interested in testing a new feature implemented by this pull request
# Why should you not test a pull request?
- Pull requests are beta code and may have bugs; bugs may cause you to crash and damage your model
- Upgrading from the stable version of INAV may require changes to your config that are not yet fully documented
# Before you proceed
- Read the comments on the pull request you want to test. It may provide useful context and information on known issues, required configuration changes or what branch of the inav-configurator is required.
- Make sure the pull request has passed all checks, otherwise you may not have pre-compiled firmware images.
- Make a diff all backup of your existing INAV configuration.
- Take notes of what INAV target you are using.
- You will need a recent version of INAV Configurator from master, or even a specific branch. If you don't need a specific branch, [inav-configurator-next](http://seyrsnys.myzen.co.uk/inav-configurator-next/) usually has recent unofficial pre-built versions of INAV Configurator. If your pull requests refers to an inav-configruator pull request, you are likely to need a specific branch of the configurator. In that case you can try to build it from source by following the build [``Instructions``](https://github.com/iNavFlight/inav-configurator#building-and-running-inav-configurator-locally-for-development) or follow instructions on how to do any needed configuration changes using the CLI.
# Finding the pull request
This is easy, but you will need to be logged in to your GitHub account.
Navigate to the INAV github project and click on [``Pull Requests``](https://github.com/iNavFlight/inav/pulls).
You can just scroll through the list to find a pull request you are interested in, or use the filter bar by typing the name of the pull request, or the number, if you know it.
![Search results](assets/pr_testing/pr_search_result.png)
Once you find the one you are looking for, go ahead an open it!
Click on the ``Checks`` tab
Click on ``Build firmware``, it should take you to the ``Actions`` tab.
![Search results](assets/pr_testing/build_firmware.png)
You should see a summary with a column saying ``Artifacts`` and a number. Click on the number to be taken to the list of artifacts.
![Search results](assets/pr_testing/actions_summary.png)
On the ``Artifacts`` list, there should be an artifact without SITL in its name.
![Search results](assets/pr_testing/artifact_listing.png)
Click on it to download the zip file containing pre-compiled firmware images for all INAV official targets. Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings.
# I have flashed the new firmware, what should I do next?
- You should configure your model, either manually from scratch, or by loading your diff file. Keep in mind that loading a diff file may not always work, as there may have been some other changes in INAV that require attention. But even if you start from scratch, there are usually many sections that are safe to copy over from your diff.
- Try to reproduce the bug reported or play around with the new feature.
- Once you are done testing, don't forget to report your results on the pull request. Both positive results and issues are valid and welcome feedback.

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 71 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 26 KiB

View file

@ -85,7 +85,7 @@ static i2cDevice_t i2cHardwareMap[I2CDEV_COUNT] = {
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1L(I2C2), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn, .af = GPIO_AF4_I2C2 }, { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1L(I2C2), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn, .af = GPIO_AF4_I2C2 },
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1L(I2C3), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn, .af = GPIO_AF4_I2C3 }, { .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1L(I2C3), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn, .af = GPIO_AF4_I2C3 },
#if defined(USE_I2C_DEVICE_4) #if defined(USE_I2C_DEVICE_4)
{ .dev = I2C4, .scl = IO_TAG(I2C4_SCL), .sda = IO_TAG(I2C4_SDA), .rcc = RCC_APB1L(I2C4), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C4_EV_IRQn, .er_irq = I2C4_ER_IRQn, .af = GPIO_AF4_I2C4 } { .dev = I2C4, .scl = IO_TAG(I2C4_SCL), .sda = IO_TAG(I2C4_SDA), .rcc = RCC_APB4(I2C4), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C4_EV_IRQn, .er_irq = I2C4_ER_IRQn, .af = GPIO_AF4_I2C4 }
#endif #endif
#endif #endif
}; };

View file

@ -453,7 +453,6 @@ static bool sdcardSpi_poll(void)
doMore: doMore:
switch (sdcard.state) { switch (sdcard.state) {
case SDCARD_STATE_RESET: case SDCARD_STATE_RESET:
busSetSpeed(sdcard.dev, BUS_SPEED_INITIALIZATION);
sdcardSpi_select(); sdcardSpi_select();
initStatus = sdcardSpi_sendCommand(SDCARD_COMMAND_GO_IDLE_STATE, 0); initStatus = sdcardSpi_sendCommand(SDCARD_COMMAND_GO_IDLE_STATE, 0);
@ -476,8 +475,6 @@ static bool sdcardSpi_poll(void)
break; break;
case SDCARD_STATE_CARD_INIT_IN_PROGRESS: case SDCARD_STATE_CARD_INIT_IN_PROGRESS:
busSetSpeed(sdcard.dev, BUS_SPEED_INITIALIZATION);
if (sdcardSpi_checkInitDone()) { if (sdcardSpi_checkInitDone()) {
if (sdcard.version == 2) { if (sdcard.version == 2) {
// Check for high capacity card // Check for high capacity card
@ -516,8 +513,6 @@ static bool sdcardSpi_poll(void)
busSetSpeed(sdcard.dev, BUS_SPEED_STANDARD); busSetSpeed(sdcard.dev, BUS_SPEED_STANDARD);
break; break;
case SDCARD_STATE_INITIALIZATION_RECEIVE_CID: case SDCARD_STATE_INITIALIZATION_RECEIVE_CID:
busSetSpeed(sdcard.dev, BUS_SPEED_INITIALIZATION);
if (sdcardSpi_receiveCID()) { if (sdcardSpi_receiveCID()) {
sdcardSpi_deselect(); sdcardSpi_deselect();
@ -881,8 +876,6 @@ void sdcardSpi_init(void)
sdcard.operationStartTime = millis(); sdcard.operationStartTime = millis();
sdcard.state = SDCARD_STATE_RESET; sdcard.state = SDCARD_STATE_RESET;
sdcard.failureCount = 0; sdcard.failureCount = 0;
busSetSpeed(sdcard.dev, BUS_SPEED_STANDARD);
} }
sdcardVTable_t sdcardSpiVTable = { sdcardVTable_t sdcardSpiVTable = {

View file

@ -127,14 +127,22 @@ void sdioPinConfigure(void)
sdioHardware = &sdioPinHardware[SDCARD_SDIO_DEVICE]; sdioHardware = &sdioPinHardware[SDCARD_SDIO_DEVICE];
sdioPin[SDIO_PIN_CK] = sdioHardware[SDCARD_SDIO_DEVICE].sdioPinCK[0]; #ifdef SDCARD_SDIO2_CK_ALT
sdioPin[SDIO_PIN_CMD] = sdioHardware[SDCARD_SDIO_DEVICE].sdioPinCMD[0]; sdioPin[SDIO_PIN_CK] = sdioHardware->sdioPinCK[1];
sdioPin[SDIO_PIN_D0] = sdioHardware[SDCARD_SDIO_DEVICE].sdioPinD0[0]; #else
sdioPin[SDIO_PIN_CK] = sdioHardware->sdioPinCK[0];
#endif
#ifdef SDCARD_SDIO2_CMD_ALT
sdioPin[SDIO_PIN_CMD] = sdioHardware->sdioPinCMD[1];
#else
sdioPin[SDIO_PIN_CMD] = sdioHardware->sdioPinCMD[0];
#endif
sdioPin[SDIO_PIN_D0] = sdioHardware->sdioPinD0[0];
#ifdef SDCARD_SDIO_4BIT #ifdef SDCARD_SDIO_4BIT
sdioPin[SDIO_PIN_D1] = sdioHardware[SDCARD_SDIO_DEVICE].sdioPinD1[0]; sdioPin[SDIO_PIN_D1] = sdioHardware->sdioPinD1[0];
sdioPin[SDIO_PIN_D2] = sdioHardware[SDCARD_SDIO_DEVICE].sdioPinD2[0]; sdioPin[SDIO_PIN_D2] = sdioHardware->sdioPinD2[0];
sdioPin[SDIO_PIN_D3] = sdioHardware[SDCARD_SDIO_DEVICE].sdioPinD3[0]; sdioPin[SDIO_PIN_D3] = sdioHardware->sdioPinD3[0];
#endif #endif
} }
@ -254,7 +262,11 @@ bool SD_Init(void)
hsd1.Init.BusWide = SDMMC_BUS_WIDE_1B; // FIXME untested hsd1.Init.BusWide = SDMMC_BUS_WIDE_1B; // FIXME untested
#endif #endif
hsd1.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_ENABLE; hsd1.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_ENABLE;
hsd1.Init.ClockDiv = 1; // 200Mhz / (2 * 1 ) = 100Mhz, used for "UltraHigh speed SD card" only, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV #ifdef SDCARD_SDIO_NORMAL_SPEED
hsd1.Init.ClockDiv = SDMMC_NSpeed_CLK_DIV;
#else
hsd1.Init.ClockDiv = 1; // 200Mhz / (2 * 1 ) = 100Mhz, used for "UltraHigh speed SD card" only, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV
#endif
status = HAL_SD_Init(&hsd1); // Will call HAL_SD_MspInit status = HAL_SD_Init(&hsd1); // Will call HAL_SD_MspInit

View file

@ -174,7 +174,7 @@ void flashLedsAndBeep(void)
LED1_TOGGLE; LED1_TOGGLE;
LED0_TOGGLE; LED0_TOGGLE;
delay(25); delay(25);
if (!(getPreferredBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) if (!(getBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1))))
BEEP_ON; BEEP_ON;
delay(25); delay(25);
BEEP_OFF; BEEP_OFF;

View file

@ -2527,6 +2527,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
gpsSol.flags.validVelNE = false; gpsSol.flags.validVelNE = false;
gpsSol.flags.validVelD = false; gpsSol.flags.validVelD = false;
gpsSol.flags.validEPE = false; gpsSol.flags.validEPE = false;
gpsSol.flags.validTime = false;
gpsSol.numSat = sbufReadU8(src); gpsSol.numSat = sbufReadU8(src);
gpsSol.llh.lat = sbufReadU32(src); gpsSol.llh.lat = sbufReadU32(src);
gpsSol.llh.lon = sbufReadU32(src); gpsSol.llh.lon = sbufReadU32(src);
@ -3538,6 +3539,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
gpsSol.flags.validVelNE = true; gpsSol.flags.validVelNE = true;
gpsSol.flags.validVelD = true; gpsSol.flags.validVelD = true;
gpsSol.flags.validEPE = true; gpsSol.flags.validEPE = true;
gpsSol.flags.validTime = false;
gpsSol.llh.lat = sbufReadU32(src); gpsSol.llh.lat = sbufReadU32(src);
gpsSol.llh.lon = sbufReadU32(src); gpsSol.llh.lon = sbufReadU32(src);
@ -3592,7 +3594,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
if (sensors(SENSOR_MAG)) { if (sensors(SENSOR_MAG)) {
mag.magADC[X] = ((int16_t)sbufReadU16(src)) / 20; // 16000 / 20 = 800uT mag.magADC[X] = ((int16_t)sbufReadU16(src)) / 20; // 16000 / 20 = 800uT
mag.magADC[Y] = ((int16_t)sbufReadU16(src)) / 20; mag.magADC[Y] = ((int16_t)sbufReadU16(src)) / 20; //note that mag failure is simulated by setting all readings to zero
mag.magADC[Z] = ((int16_t)sbufReadU16(src)) / 20; mag.magADC[Z] = ((int16_t)sbufReadU16(src)) / 20;
} else { } else {
sbufAdvance(src, sizeof(uint16_t) * XYZ_AXIS_COUNT); sbufAdvance(src, sizeof(uint16_t) * XYZ_AXIS_COUNT);
@ -3609,8 +3611,16 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
#endif #endif
if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) {
simulatorData.airSpeed = sbufReadU16(src); simulatorData.airSpeed = sbufReadU16(src);
} } else {
if (SIMULATOR_HAS_OPTION(HITL_EXTENDED_FLAGS)) {
sbufReadU16(src);
}
}
if (SIMULATOR_HAS_OPTION(HITL_EXTENDED_FLAGS)) {
simulatorData.flags |= ((uint16_t)sbufReadU8(src)) << 8;
}
} else { } else {
DISABLE_STATE(GPS_FIX); DISABLE_STATE(GPS_FIX);
} }

View file

@ -175,20 +175,23 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void);
typedef enum { typedef enum {
HITL_RESET_FLAGS = (0 << 0), HITL_RESET_FLAGS = (0 << 0),
HITL_ENABLE = (1 << 0), HITL_ENABLE = (1 << 0),
HITL_SIMULATE_BATTERY = (1 << 1), HITL_SIMULATE_BATTERY = (1 << 1),
HITL_MUTE_BEEPER = (1 << 2), HITL_MUTE_BEEPER = (1 << 2),
HITL_USE_IMU = (1 << 3), // Use the Acc and Gyro data provided by XPlane to calculate Attitude (i.e. 100% of the calculations made by AHRS from INAV) HITL_USE_IMU = (1 << 3), // Use the Acc and Gyro data provided by XPlane to calculate Attitude (i.e. 100% of the calculations made by AHRS from INAV)
HITL_HAS_NEW_GPS_DATA = (1 << 4), HITL_HAS_NEW_GPS_DATA = (1 << 4),
HITL_EXT_BATTERY_VOLTAGE = (1 << 5), // Extend MSP_SIMULATOR format 2 HITL_EXT_BATTERY_VOLTAGE = (1 << 5), // Extend MSP_SIMULATOR format 2
HITL_AIRSPEED = (1 << 6) HITL_AIRSPEED = (1 << 6),
HITL_EXTENDED_FLAGS = (1 << 7), // Extend MSP_SIMULATOR format 2
HITL_GPS_TIMEOUT = (1 << 8),
HITL_PITOT_FAILURE = (1 << 9)
} simulatorFlags_t; } simulatorFlags_t;
typedef struct { typedef struct {
simulatorFlags_t flags; simulatorFlags_t flags;
uint8_t debugIndex; uint8_t debugIndex;
uint8_t vbat; // 126 -> 12.6V uint8_t vbat; // 126 -> 12.6V
uint16_t airSpeed; // cm/s uint16_t airSpeed; // cm/s
int16_t input[4]; int16_t input[4];
} simulatorData_t; } simulatorData_t;

View file

@ -218,7 +218,7 @@ static const beeperTableEntry_t *currentBeeperEntry = NULL;
*/ */
void beeper(beeperMode_e mode) void beeper(beeperMode_e mode)
{ {
if (mode == BEEPER_SILENCE || ((getBeeperOffMask() & (1 << (BEEPER_USB-1))) && (feature(FEATURE_VBAT) && (getBatteryCellCount() < 2))) || IS_RC_MODE_ACTIVE(BOXBEEPERMUTE)) { if (mode == BEEPER_SILENCE || ((getBeeperOffMask() & (1 << (BEEPER_USB-1))) && (feature(FEATURE_VBAT) && (getBatteryState() == BATTERY_NOT_PRESENT))) || IS_RC_MODE_ACTIVE(BOXBEEPERMUTE)) {
beeperSilence(); beeperSilence();
return; return;
} }

View file

@ -343,10 +343,21 @@ bool gpsUpdate(void)
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { if (ARMING_FLAG(SIMULATOR_MODE_HITL)) {
gpsUpdateTime(); if ( SIMULATOR_HAS_OPTION(HITL_GPS_TIMEOUT))
gpsSetState(GPS_RUNNING); {
sensorsSet(SENSOR_GPS); gpsSetState(GPS_LOST_COMMUNICATION);
return gpsSol.flags.hasNewData; sensorsClear(SENSOR_GPS);
gpsStats.timeouts = 5;
return false;
}
else
{
gpsSetState(GPS_RUNNING);
sensorsSet(SENSOR_GPS);
bool res = gpsSol.flags.hasNewData;
gpsSol.flags.hasNewData = false;
return res;
}
} }
#endif #endif

View file

@ -4239,12 +4239,19 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page)
bool efficiencyValid = totalDistance >= 10000; bool efficiencyValid = totalDistance >= 10000;
if (feature(FEATURE_GPS)) { if (feature(FEATURE_GPS)) {
displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :"); displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :");
uint8_t digits = 3U; // Total number of digits (including decimal point)
#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values
if (isBfCompatibleVideoSystem(osdConfig())) {
// Add one digit so no switch to scaled decimal occurs above 99
digits = 4U;
}
#endif
switch (osdConfig()->units) { switch (osdConfig()->units) {
case OSD_UNIT_UK: case OSD_UNIT_UK:
FALLTHROUGH; FALLTHROUGH;
case OSD_UNIT_IMPERIAL: case OSD_UNIT_IMPERIAL:
if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) {
moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, 3); moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits);
if (!moreThanAh) { if (!moreThanAh) {
tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1);
} else { } else {
@ -4257,7 +4264,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page)
buff[5] = '\0'; buff[5] = '\0';
} }
} else { } else {
osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, 3); osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits);
tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI);
if (!efficiencyValid) { if (!efficiencyValid) {
buff[0] = buff[1] = buff[2] = '-'; buff[0] = buff[1] = buff[2] = '-';
@ -4266,7 +4273,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page)
break; break;
case OSD_UNIT_GA: case OSD_UNIT_GA:
if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) {
moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, 3); moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits);
if (!moreThanAh) { if (!moreThanAh) {
tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1);
} else { } else {
@ -4279,7 +4286,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page)
buff[5] = '\0'; buff[5] = '\0';
} }
} else { } else {
osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, 3); osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits);
tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM);
if (!efficiencyValid) { if (!efficiencyValid) {
buff[0] = buff[1] = buff[2] = '-'; buff[0] = buff[1] = buff[2] = '-';
@ -4290,7 +4297,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page)
FALLTHROUGH; FALLTHROUGH;
case OSD_UNIT_METRIC: case OSD_UNIT_METRIC:
if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) {
moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, 3); moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits);
if (!moreThanAh) { if (!moreThanAh) {
tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1);
} else { } else {
@ -4303,7 +4310,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page)
buff[5] = '\0'; buff[5] = '\0';
} }
} else { } else {
osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, 3); osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits);
tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM);
if (!efficiencyValid) { if (!efficiencyValid) {
buff[0] = buff[1] = buff[2] = '-'; buff[0] = buff[1] = buff[2] = '-';

View file

@ -199,7 +199,7 @@ PG_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig,
void batteryInit(void) void batteryInit(void)
{ {
batteryState = BATTERY_NOT_PRESENT; batteryState = BATTERY_NOT_PRESENT;
batteryCellCount = 1; batteryCellCount = 0;
batteryFullVoltage = 0; batteryFullVoltage = 0;
batteryWarningVoltage = 0; batteryWarningVoltage = 0;
batteryCriticalVoltage = 0; batteryCriticalVoltage = 0;

View file

@ -62,12 +62,17 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void)
hardwareSensorStatus_e getHwCompassStatus(void) hardwareSensorStatus_e getHwCompassStatus(void)
{ {
#if defined(USE_MAG)
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
if ((ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) && sensors(SENSOR_MAG)) { if ((ARMING_FLAG(SIMULATOR_MODE_HITL) || ARMING_FLAG(SIMULATOR_MODE_SITL)) && sensors(SENSOR_MAG)) {
return HW_SENSOR_OK; if (compassIsHealthy()) {
return HW_SENSOR_OK;
}
else {
return HW_SENSOR_UNHEALTHY;
}
} }
#endif #endif
#if defined(USE_MAG)
if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) { if (detectedSensors[SENSOR_INDEX_MAG] != MAG_NONE) {
if (compassIsHealthy()) { if (compassIsHealthy()) {
return HW_SENSOR_OK; return HW_SENSOR_OK;

View file

@ -194,6 +194,13 @@ STATIC_PROTOTHREAD(pitotThread)
pt1FilterInit(&pitot.lpfState, pitotmeterConfig()->pitot_lpf_milli_hz / 1000.0f, 0.0f); pt1FilterInit(&pitot.lpfState, pitotmeterConfig()->pitot_lpf_milli_hz / 1000.0f, 0.0f);
while(1) { while(1) {
#ifdef USE_SIMULATOR
while (SIMULATOR_HAS_OPTION(HITL_AIRSPEED) && SIMULATOR_HAS_OPTION(HITL_PITOT_FAILURE))
{
ptDelayUs(10000);
}
#endif
// Start measurement // Start measurement
if (pitot.dev.start(&pitot.dev)) { if (pitot.dev.start(&pitot.dev)) {
pitot.lastSeenHealthyMs = millis(); pitot.lastSeenHealthyMs = millis();
@ -208,9 +215,9 @@ STATIC_PROTOTHREAD(pitotThread)
pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL); pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL);
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) {
pitotPressureTmp = sq(simulatorData.airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE; pitotPressureTmp = sq(simulatorData.airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE;
} }
#endif #endif
#if defined(USE_PITOT_FAKE) #if defined(USE_PITOT_FAKE)
if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) {
@ -241,14 +248,14 @@ STATIC_PROTOTHREAD(pitotThread)
pitot.airSpeed = 0.0f; pitot.airSpeed = 0.0f;
} }
#ifdef USE_SIMULATOR #ifdef USE_SIMULATOR
if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) {
pitot.airSpeed = simulatorData.airSpeed; pitot.airSpeed = simulatorData.airSpeed;
} }
#endif #endif
#if defined(USE_PITOT_FAKE) #if defined(USE_PITOT_FAKE)
if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) { if (pitotmeterConfig()->pitot_hardware == PITOT_FAKE) {
pitot.airSpeed = fakePitotGetAirspeed(); pitot.airSpeed = fakePitotGetAirspeed();
} }
#endif #endif
} }

View file

@ -26,5 +26,5 @@
void targetConfiguration(void) void targetConfiguration(void)
{ {
boardAlignmentMutable()->yawDeciDegrees = 450; //boardAlignmentMutable()->yawDeciDegrees = 450;
} }

View file

@ -81,16 +81,16 @@
#define UART2_RX_PIN PA3 #define UART2_RX_PIN PA3
#define USE_UART3 #define USE_UART3
#define UART3_TX_PIN PC11 #define UART3_TX_PIN PC10
#define UART3_RX_PIN PC10 #define UART3_RX_PIN PC11
#define USE_UART4 #define USE_UART4
#define UART4_TX_PIN PA0 #define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1 #define UART4_RX_PIN PA1
#define USE_UART5 #define USE_UART5
#define UART5_TX_PIN PC12 #define UART5_TX_PIN PD2
#define UART5_RX_PIN PD2 #define UART5_RX_PIN PC12
#define SERIAL_PORT_COUNT 6 #define SERIAL_PORT_COUNT 6

View file

@ -48,6 +48,7 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM
}; };

View file

@ -28,6 +28,7 @@
#define BEEPER PA15 #define BEEPER PA15
#define BEEPER_INVERTED #define BEEPER_INVERTED
#define BEEPER_PWM_FREQUENCY 2500
// *************** IMU generic *********************** // *************** IMU generic ***********************
#define USE_DUAL_GYRO #define USE_DUAL_GYRO

View file

@ -0,0 +1 @@
target_stm32h743xi(FOXEERH743)

View file

@ -0,0 +1,57 @@
/*
* 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 "common/axis.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "drivers/sensor.h"
#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "drivers/serial.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "rx/rx.h"
#include "io/serial.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "telemetry/telemetry.h"
#include "io/piniobox.h"
void targetConfiguration(void)
{
/*
* UART1 is SerialRX
*/
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL;
}

View file

@ -0,0 +1,47 @@
/*
* 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"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4
DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5
DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 6), // S7
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 7), // S8
DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9
DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,165 @@
/*
* 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 "F743"
#define USBD_PRODUCT_STRING "FOXEERH743"
#define USE_TARGET_CONFIG
#define LED0 PC13
#define BEEPER PD2
#define BEEPER_INVERTED
// *************** SPI1 OSD ****************
#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_MAX7456
#define MAX7456_SPI_BUS BUS_SPI1
#define MAX7456_CS_PIN PA4
// *************** SPI2 Gyro ***********************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW0_DEG
#define MPU6000_SPI_BUS BUS_SPI2
#define MPU6000_CS_PIN PB12
// *************** SPI3 FLASH ***********************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define SPI3_NSS_PIN PA15
#define M25P16_SPI_BUS BUS_SPI3
#define M25P16_CS_PIN SPI3_NSS_PIN
#define W25N01G_SPI_BUS BUS_SPI3
#define W25N01G_CS_PIN SPI3_NSS_PIN
#define USE_BLACKBOX
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_FLASH_W25N01G
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** 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_DPS310
#define USE_BARO_SPL06
#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
#define USE_MAG_VCM5883
#define TEMPERATURE_I2C_BUS BUS_I2C1
#define PITOT_I2C_BUS BUS_I2C1
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
// *************** UART *****************************
#define USE_VCP
#define USE_UART1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define USE_UART2
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define USE_UART3
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define USE_UART4
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define USE_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define USE_UART7
#define UART7_TX_PIN PE8
#define UART7_RX_PIN PE7
#define USE_UART8
#define UART8_TX_PIN PE1
#define UART8_RX_PIN PE0
#define SERIAL_PORT_COUNT 8
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PC3
#define ADC_CHANNEL_2_PIN PC5
#define ADC_CHANNEL_3_PIN PC2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define RSSI_ADC_CHANNEL ADC_CHN_2
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
// *************** LEDSTRIP ************************
#define USE_LED_STRIP
#define WS2811_PIN PA8
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL)
#define CURRENT_METER_SCALE 100
#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 0xffff
#define MAX_PWM_OUTPUT_PORTS 8
#define USE_DSHOT
#define USE_ESC_SENSOR

View file

@ -0,0 +1 @@
target_stm32h743xi(KAKUTEH7WING HSE_MHZ 16)

View file

@ -0,0 +1,36 @@
/*
* This file is part of Cleanflight.
*
* 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 "fc/fc_msp_box.h"
#include "fc/config.h"
#include "io/piniobox.h"
#include "drivers/serial.h"
#include "io/serial.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
pinioBoxConfigMutable()->permanentId[2] = BOX_PERMANENT_ID_USER3;
pinioBoxConfigMutable()->permanentId[3] = BOX_PERMANENT_ID_USER4;
beeperConfigMutable()->pwmMode = true;
}

View file

@ -0,0 +1,59 @@
/*
* This file is part of Cleanflight.
*
* 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 <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "build/build_config.h"
#include "drivers/time.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
void initialisePreBootHardware(void)
{
// VDD_3V3_SENSORS_EN
IOInit(DEFIO_IO(PB2), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PB2), IOCFG_OUT_PP);
// IOLo(DEFIO_IO(PB2));
// delay(100);
IOHi(DEFIO_IO(PB2));
// CAM Switch / User3
IOInit(DEFIO_IO(PC13), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PC13), IOCFG_OUT_PP);
IOLo(DEFIO_IO(PC13));
// User1
IOInit(DEFIO_IO(PD4), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PD4), IOCFG_OUT_PP);
IOLo(DEFIO_IO(PD4));
// VTx 9V Switch / User4
IOInit(DEFIO_IO(PE3), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PE3), IOCFG_OUT_PP);
IOHi(DEFIO_IO(PE3));
// User2
IOInit(DEFIO_IO(PE4), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
IOConfigGPIO(DEFIO_IO(PE4), IOCFG_OUT_PP);
IOLo(DEFIO_IO(PE4));
}

View file

@ -0,0 +1,57 @@
/*
* 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_bmi088_gyro, DEVHW_BMI088_GYRO, BMI088_SPI_BUS, BMI088_GYRO_CS_PIN, BMI088_GYRO_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI088_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_bmi088_acc, DEVHW_BMI088_ACC, BMI088_SPI_BUS, BMI088_ACC_CS_PIN, BMI088_ACC_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_BMI088_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
// BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2
DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3
DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4
DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5
DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 DMA_NONE
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S7
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S8
DEF_TIM(TIM15,CH1, PE5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S9
DEF_TIM(TIM15,CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S13
//DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S14 / LED_2812
DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // S14 / LED_2812
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,204 @@
/*
* 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 "KH7W"
#define USBD_PRODUCT_STRING "KAKUTEH7WING"
#define USE_HARDWARE_PREBOOT_SETUP
#define USE_TARGET_CONFIG
#define LED0 PC15
#define LED1 PC14
#define BEEPER PB9
#define BEEPER_INVERTED
// *************** IMU generic ***********************
// #define USE_DUAL_GYRO
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
// *************** SPI1 IMU0 BMI088 ******************
#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_BMI088
#define IMU_BMI088_ALIGN CW0_DEG
#define BMI088_SPI_BUS BUS_SPI1
#define BMI088_GYRO_CS_PIN PC9
#define BMI088_GYRO_EXTI_PIN PD10
#define BMI088_ACC_CS_PIN PC8
#define BMI088_ACC_EXTI_PIN PD11
// *************** SPI3 IMU1 ICM42688 ************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW90_DEG
#define ICM42605_SPI_BUS BUS_SPI3
#define ICM42605_CS_PIN PE12
#define ICM42605_EXTI_PIN PE15
// *************** SPI2 OSD ***********************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PD3
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC3
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// *************** SDIO SD BLACKBOX*******************
#define USE_SDCARD
#define USE_SDCARD_SDIO
#define SDCARD_SDIO_DEVICE SDIODEV_2
#define SDCARD_SDIO_4BIT
#define SDCARD_SDIO_NORMAL_SPEED
#define SDCARD_SDIO2_CMD_ALT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
// *************** I2C /Baro/Mag *********************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB7
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11
#define USE_I2C_DEVICE_4
#define I2C4_SCL PD12
#define I2C4_SDA PD13
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C4
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#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
#define USE_MAG_VCM5883
#define TEMPERATURE_I2C_BUS BUS_I2C1
#define PITOT_I2C_BUS BUS_I2C1
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
// *************** UART *****************************
#define USE_VCP
#define VBUS_SENSING_PIN PA9
#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 PD8
#define UART3_RX_PIN PD9
#define USE_UART5
#define UART5_TX_PIN PB13
#define UART5_RX_PIN PD2
#define USE_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define USE_UART7
#define UART7_TX_PIN PE8
#define UART7_RX_PIN PE7
#define USE_UART8
#define UART8_TX_PIN PE1
#define UART8_RX_PIN PE0
#define SERIAL_PORT_COUNT 8
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART6
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PC5 //VBAT1
#define ADC_CHANNEL_2_PIN PC4 //CURR1
#define ADC_CHANNEL_3_PIN PC0 //RSSI
#define ADC_CHANNEL_5_PIN PA3 //VB2
#define ADC_CHANNEL_6_PIN PA2 //CU2
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// *************** PINIO ***************************
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PC13 // VTX power switcher
#define PINIO2_PIN PE3 // 2xCamera switcher
#define PINIO3_PIN PD4 // User1
#define PINIO4_PIN PE4 // User2
// *************** LEDSTRIP ************************
#define USE_LED_STRIP
#define WS2811_PIN PA15
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
#define CURRENT_METER_SCALE 3660 // 36.6
#define VBAT_SCALE_DEFAULT 1818 // 18.18
#define VBAT_SCALE_DEFAULT2 1100 // 11.0
#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 0xffff
#define MAX_PWM_OUTPUT_PORTS 14
#define USE_DSHOT
#define USE_ESC_SENSOR

View file

@ -256,6 +256,8 @@ static void SystemClockHSE_Config(void)
pllConfig_t *pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY; pllConfig_t *pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
#endif #endif
pll1Config->m = HSE_VALUE / 1000000 / 2; // correction for different HSE_VALUE
// Configure voltage scale. // Configure voltage scale.
// It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1, // It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1,
// and it may stay or overridden by PWR_REGULATOR_VOLTAGE_SCALE0 depending on the clock config. // and it may stay or overridden by PWR_REGULATOR_VOLTAGE_SCALE0 depending on the clock config.