Skip to content

Commit

Permalink
Merge branch 'master' into MrD_Keep-arm-status-over-MSP-if-in-emergen…
Browse files Browse the repository at this point in the history
…cy-re-arm-period
  • Loading branch information
MrD-RC committed Oct 30, 2024
2 parents 5311894 + fccc76c commit 9151052
Show file tree
Hide file tree
Showing 19 changed files with 722 additions and 178 deletions.
12 changes: 6 additions & 6 deletions docs/Navigation.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@ The navigation system in INAV is responsible for assisting the pilot allowing al
## NAV ALTHOLD mode - altitude hold

Altitude hold requires a valid source of altitude - barometer, GPS or rangefinder. The best source is chosen automatically.
In this mode THROTTLE stick controls climb rate (vertical velocity). When pilot moves stick up - quad goes up, pilot moves stick down - quad descends, you keep stick at neutral position - quad hovers.
In this mode THROTTLE stick controls climb rate (vertical velocity). When pilot moves stick up - aircraft goes up, pilot moves stick down -
aircraft descends, you keep stick at neutral position - aircraft maintains current altitude.

By default, GPS is available as an altitude source for airplanes only. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled.

### CLI parameters affecting ALTHOLD mode:
* *nav_use_midthr_for_althold* - when set to "0", firmware will remember where your throttle stick was when ALTHOLD was activated - this will be considered neutral position. When set to "1" - 50% throttle will be considered neutral position.
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.


### Related PIDs
PIDs affecting altitude hold: ALT & VEL
Expand All @@ -25,12 +25,12 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co

## NAV POSHOLD mode - position hold

Position hold requires GPS, accelerometer and compass sensors. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
Position hold requires GPS, accelerometer and compass sensors. Multirotor requires barometer, unless is enabled. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From INAV 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.

### CLI parameters affecting POSHOLD mode:
* *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.


### Related PIDs
PIDs affecting position hold: POS, POSR
Expand All @@ -42,7 +42,7 @@ PID meaning:

Home for RTH is the position where vehicle was first armed. This position may be offset by the CLI settings `nav_rth_home_offset_distance` and `nav_rth_home_offset_direction`. This position may also be overridden with Safehomes. RTH requires accelerometer, compass and GPS sensors.

RTH requires barometer for multirotor, unless unless *inav_use_gps_no_baro* is enabled.
RTH requires barometer for multirotor.

RTH will maintain altitude during the return. When home is reached, a copter will attempt automated landing. An airplane will either loiter around the home position, or attempt an automated landing, depending on your settings.
When deciding what altitude to maintain, RTH has 6 different modes of operation (controlled by *nav_rth_alt_mode* and *nav_rth_altitude* cli variables):
Expand Down
42 changes: 41 additions & 1 deletion docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -2002,6 +2002,16 @@ Uncertainty value for barometric sensor [cm]

---

### inav_default_alt_sensor

Sets the default altitude sensor to use. Settings GPS and BARO always use both sensors unless there is an altitude error between the sensors that exceeds a set limit. In this case only the selected sensor will be used while the altitude error limit is exceeded. GPS error limit = 2 * inav_max_eph_epv. BARO error limit = 4 * inav_baro_epv. Settings GPS_ONLY and BARO_ONLY will use only the selected sensor even if the other sensor is working. The other sensor will only be used as a backup if the selected sensor is no longer available to use.

| Default | Min | Max |
| --- | --- | --- |
| GPS | | |

---

### inav_gravity_cal_tolerance

Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value.
Expand Down Expand Up @@ -2122,6 +2132,16 @@ Weight of barometer measurements in estimated altitude and climb rate. Setting i

---

### inav_w_z_baro_v

Weight of barometer climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors.

| Default | Min | Max |
| --- | --- | --- |
| 0.1 | 0 | 10 |

---

### inav_w_z_gps_p

Weight of GPS altitude measurements in estimated altitude. Setting is used on both airplanes and multirotors.
Expand Down Expand Up @@ -4562,6 +4582,26 @@ Value above which the OSD current consumption element will start blinking. Measu

---

### osd_decimals_altitude

Number of decimals for the altitude displayed in the OSD [3-5].

| Default | Min | Max |
| --- | --- | --- |
| 3 | 3 | 5 |

---

### osd_decimals_distance

Number of decimals for distance displayed in the OSD [3-5]. This includes distance from home, total distance, and distance remaining.

| Default | Min | Max |
| --- | --- | --- |
| 3 | 3 | 5 |

---

### osd_dist_alarm

Value above which to make the OSD distance from home indicator blink (meters)
Expand Down Expand Up @@ -4928,7 +4968,7 @@ Number of digits used for mAh precision. Currently used by mAh Used and Battery

| Default | Min | Max |
| --- | --- | --- |
| 4 | 4 | 6 |
| 4 | 3 | 6 |

---

Expand Down
8 changes: 8 additions & 0 deletions readme.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,11 @@
# INAV 8.0 feature freeze

It is that time of the year again, and the time for a new INAV release is near!

The current plan is to have a feature freeze on **15th of November 2024**.

For a preview of what is comming, have a look at ![milestone 8.0](https://github.com/iNavFlight/inav/milestone/43).

# INAV - navigation capable flight controller

# F411 PSA
Expand Down
134 changes: 103 additions & 31 deletions src/main/drivers/serial_uart_at32f43x.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,28 +36,37 @@ typedef struct uartDevice_s {
usart_type* dev;
uartPort_t port;
ioTag_t rx;
uint8_t rx_af;
ioTag_t tx;
uint8_t tx_af;
volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
uint32_t rcc_ahb1;
rccPeriphTag_t rcc_apb2;
rccPeriphTag_t rcc_apb1;
uint8_t af;
uint8_t irq;
uint32_t irqPriority;
bool pinSwap;
} uartDevice_t;

#ifdef USE_UART1
static uartDevice_t uart1 =
{
static uartDevice_t uart1 = {
.dev = USART1,
.rx = IO_TAG(UART1_RX_PIN),
.tx = IO_TAG(UART1_TX_PIN),
#ifdef UART1_AF
.af = CONCAT(GPIO_MUX_, UART1_AF),
#if defined(UART1_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART1_RX_AF),
#elif defined(UART1_AF)
.rx_af = CONCAT(GPIO_MUX_, UART1_AF),
#else
.rx_af = GPIO_MUX_7,
#endif
#if defined(UART1_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART1_TX_AF),
#elif defined(UART1_AF)
.tx_af = CONCAT(GPIO_MUX_, UART1_AF),
#else
.af = GPIO_MUX_7,
.tx_af = GPIO_MUX_7,
#endif
#ifdef UART1_AHB1_PERIPHERALS
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
Expand All @@ -79,10 +88,19 @@ static uartDevice_t uart2 =
.dev = USART2,
.rx = IO_TAG(UART2_RX_PIN),
.tx = IO_TAG(UART2_TX_PIN),
#ifdef UART2_AF
.af = CONCAT(GPIO_MUX_, UART2_AF),
#if defined(UART2_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART2_RX_AF),
#elif defined(UART2_AF)
.rx_af = CONCAT(GPIO_MUX_, UART2_AF),
#else
.rx_af = GPIO_MUX_7,
#endif
#if defined(UART2_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART2_TX_AF),
#elif defined(UART2_AF)
.tx_af = CONCAT(GPIO_MUX_, UART2_AF),
#else
.af = GPIO_MUX_7,
.tx_af = GPIO_MUX_7,
#endif
#ifdef UART2_AHB1_PERIPHERALS
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
Expand All @@ -104,10 +122,19 @@ static uartDevice_t uart3 =
.dev = USART3,
.rx = IO_TAG(UART3_RX_PIN),
.tx = IO_TAG(UART3_TX_PIN),
#ifdef UART3_AF
.af = CONCAT(GPIO_MUX_, UART3_AF),
#if defined(UART3_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART3_RX_AF),
#elif defined(UART3_AF)
.rx_af = CONCAT(GPIO_MUX_, UART3_AF),
#else
.af = GPIO_MUX_7,
.rx_af = GPIO_MUX_7,
#endif
#if defined(UART3_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART3_TX_AF),
#elif defined(UART3_AF)
.tx_af = CONCAT(GPIO_MUX_, UART3_AF),
#else
.tx_af = GPIO_MUX_7,
#endif
#ifdef UART3_AHB1_PERIPHERALS
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
Expand All @@ -129,10 +156,19 @@ static uartDevice_t uart4 =
.dev = UART4,
.rx = IO_TAG(UART4_RX_PIN),
.tx = IO_TAG(UART4_TX_PIN),
#ifdef UART4_AF
.af = CONCAT(GPIO_MUX_, UART4_AF),
#if defined(UART4_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART4_RX_AF),
#elif defined(UART4_AF)
.rx_af = CONCAT(GPIO_MUX_, UART4_AF),
#else
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART4_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART4_TX_AF),
#elif defined(UART4_AF)
.tx_af = CONCAT(GPIO_MUX_, UART4_AF),
#else
.af = GPIO_MUX_8,
.tx_af = GPIO_MUX_8,
#endif
#ifdef UART4_AHB1_PERIPHERALS
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
Expand All @@ -154,10 +190,19 @@ static uartDevice_t uart5 =
.dev = UART5,
.rx = IO_TAG(UART5_RX_PIN),
.tx = IO_TAG(UART5_TX_PIN),
#ifdef UART5_AF
.af = CONCAT(GPIO_MUX_, UART5_AF),
#if defined(UART5_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART5_RX_AF),
#elif defined(UART5_AF)
.rx_af = CONCAT(GPIO_MUX_, UART5_AF),
#else
.af = GPIO_MUX_8,
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART5_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART5_TX_AF),
#elif defined(UART5_AF)
.tx_af = CONCAT(GPIO_MUX_, UART5_AF),
#else
.tx_af = GPIO_MUX_8,
#endif
#ifdef UART5_AHB1_PERIPHERALS
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
Expand All @@ -179,10 +224,19 @@ static uartDevice_t uart6 =
.dev = USART6,
.rx = IO_TAG(UART6_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN),
#ifdef UART6_AF
.af = CONCAT(GPIO_MUX_, UART6_AF),
#if defined(UART6_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART6_RX_AF),
#elif defined(UART6_AF)
.rx_af = CONCAT(GPIO_MUX_, UART6_AF),
#else
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART6_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART6_TX_AF),
#elif defined(UART6_AF)
.tx_af = CONCAT(GPIO_MUX_, UART6_AF),
#else
.af = GPIO_MUX_8,
.tx_af = GPIO_MUX_8,
#endif
#ifdef UART6_AHB1_PERIPHERALS
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
Expand All @@ -204,10 +258,19 @@ static uartDevice_t uart7 =
.dev = UART7,
.rx = IO_TAG(UART7_RX_PIN),
.tx = IO_TAG(UART7_TX_PIN),
#ifdef UART7_AF
.af = CONCAT(GPIO_MUX_, UART7_AF),
#if defined(UART7_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART7_RX_AF),
#elif defined(UART7_AF)
.rx_af = CONCAT(GPIO_MUX_, UART7_AF),
#else
.af = GPIO_MUX_8,
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART7_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART7_TX_AF),
#elif defined(UART7_AF)
.tx_af = CONCAT(GPIO_MUX_, UART7_AF),
#else
.tx_af = GPIO_MUX_8,
#endif
.rcc_apb1 = RCC_APB1(UART7),
.irq = UART7_IRQn,
Expand All @@ -226,10 +289,19 @@ static uartDevice_t uart8 =
.dev = UART8,
.rx = IO_TAG(UART8_RX_PIN),
.tx = IO_TAG(UART8_TX_PIN),
#ifdef UART8_AF
.af = CONCAT(GPIO_MUX_, UART8_AF),
#if defined(UART8_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART8_RX_AF),
#elif defined(UART8_AF)
.rx_af = CONCAT(GPIO_MUX_, UART8_AF),
#else
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART8_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART8_TX_AF),
#elif defined(UART8_AF)
.tx_af = CONCAT(GPIO_MUX_, UART8_AF),
#else
.af = GPIO_MUX_8,
.tx_af = GPIO_MUX_8,
#endif
.rcc_apb1 = RCC_APB1(UART8),
.irq = UART8_IRQn,
Expand Down Expand Up @@ -389,22 +461,22 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode,
if (options & SERIAL_BIDIR) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
if (options & SERIAL_BIDIR_PP) {
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->tx_af);
} else {
IOConfigGPIOAF(tx,
(options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_OD : IOCFG_AF_OD_UP,
uart->af);
uart->tx_af);
}
}
else {
if (mode & MODE_TX) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->rx_af);
}

if (mode & MODE_RX) {
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->rx_af);
}
}

Expand Down
6 changes: 3 additions & 3 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -2524,11 +2524,11 @@ static void osdCustom(char *cmdline){
int32_t i = args[INDEX];
if (
i >= 0 && i < MAX_CUSTOM_ELEMENTS &&
args[PART0_TYPE] >= 0 && args[PART0_TYPE] <= 7 &&
args[PART0_TYPE] >= 0 && args[PART0_TYPE] <= 26 &&
args[PART0_VALUE] >= 0 && args[PART0_VALUE] <= UINT8_MAX &&
args[PART1_TYPE] >= 0 && args[PART1_TYPE] <= 7 &&
args[PART1_TYPE] >= 0 && args[PART1_TYPE] <= 26 &&
args[PART1_VALUE] >= 0 && args[PART1_VALUE] <= UINT8_MAX &&
args[PART2_TYPE] >= 0 && args[PART2_TYPE] <= 7 &&
args[PART2_TYPE] >= 0 && args[PART2_TYPE] <= 26 &&
args[PART2_VALUE] >= 0 && args[PART2_VALUE] <= UINT8_MAX &&
args[VISIBILITY_TYPE] >= 0 && args[VISIBILITY_TYPE] <= 2 &&
args[VISIBILITY_VALUE] >= 0 && args[VISIBILITY_VALUE] <= UINT8_MAX
Expand Down
12 changes: 12 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1702,6 +1702,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
}
break;

case MSP2_INAV_ESC_TELEM:
{
uint8_t motorCount = getMotorCount();
sbufWriteU8(dst, motorCount);

for (uint8_t i = 0; i < motorCount; i++){
const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry
sbufWriteDataSafe(dst, escState, sizeof(escSensorData_t));
}
}
break;
#endif

#ifdef USE_EZ_TUNE
Expand Down
Loading

0 comments on commit 9151052

Please sign in to comment.