Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/master' into custom_24
Browse files Browse the repository at this point in the history
  • Loading branch information
breadoven committed Oct 7, 2024
2 parents 357e00f + 806b47a commit e85c522
Show file tree
Hide file tree
Showing 24 changed files with 524 additions and 187 deletions.
13 changes: 12 additions & 1 deletion docs/OSD.md
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,18 @@ Here are the OSD Elements provided by INAV.
| 144 | OSD_MULTI_FUNCTION | 7.0.0 | |
| 145 | OSD_ODOMETER | 7.0.0 | For this to work correctly, stats must be enabled (`set stats=ON`). Otherwise, this will show the total flight distance. |
| 146 | OSD_PILOT_LOGO | 7.0.0 | |
| 147 | OSD_BLACKBOX | 8.0.0 | The element will be hidden unless blackbox recording is attempted. |
| 147 | OSD_CUSTOM_ELEMENT_1 | 7.0.0 | |
| 148 | OSD_CUSTOM_ELEMENT_2 | 7.0.0 | |
| 149 | OSD_CUSTOM_ELEMENT_3 | 7.0.0 | |
| 150 | OSD_ADSB_WARNING | 7.0.0 | |
| 151 | OSD_ADSB_INFO | 7.0.0 | |
| 152 | OSD_BLACKBOX | 8.0.0 | The element will be hidden unless blackbox recording is attempted. |
| 153 | OSD_FORMATION_FLIGHT | 8.0.0 | |
| 154 | OSD_CUSTOM_ELEMENT_4 | 8.0.0 | |
| 155 | OSD_CUSTOM_ELEMENT_5 | 8.0.0 | |
| 156 | OSD_CUSTOM_ELEMENT_6 | 8.0.0 | |
| 157 | OSD_CUSTOM_ELEMENT_7 | 8.0.0 | |
| 158 | OSD_CUSTOM_ELEMENT_8 | 8.0.0 | |

# Pilot Logos

Expand Down
14 changes: 11 additions & 3 deletions docs/Programming Framework.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ INAV Programming Framework consists of:
IPF can be edited using INAV Configurator user interface, or via CLI. To use COnfigurator, click the tab labeled
"Programming". The various options shown in Configurator are described below.

**Note:** IPF uses integer math. If your programming line returns a decimal, it will be truncated to an integer. So if your math is `1` / `3` = , IPF will truncate the decimal and return `0`.

## Logic Conditions

### CLI
Expand Down Expand Up @@ -61,9 +63,8 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
| 14 | Basic: Add | Add `Operand A` to `Operand B` and returns the result |
| 15 | Basic: Subtract | Substract `Operand B` from `Operand A` and returns the result |
| 16 | Basic: Multiply | Multiply `Operand A` by `Operand B` and returns the result |
| 17 | Basic: Divide | Divide `Operand A` by `Operand B` and returns the result |
| 18 | Set GVAR | Store value from `Operand B` into the Global Variable addressed by
`Operand A`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
| 17 | Basic: Divide | Divide `Operand A` by `Operand B` and returns the result. NOTE: If `Operand B` = `0`, the `Divide` operation will simply return `Operand A`|
| 18 | Set GVAR | Store value from `Operand B` into the Global Variable addressed by `Operand A`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
| 19 | Increase GVAR | Increase the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
| 20 | Decrease GVAR | Decrease the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
| 21 | Set IO Port | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
Expand Down Expand Up @@ -233,8 +234,15 @@ All flags are reseted on ARM and DISARM event.

`gvar <index> <default value> <min> <max>`

**Note:** Global Variables (GVARs) are limited to integers between negative `-32768` and positive `32767`.

## Programming PID

IPF makes a set of general user PIDFF controllers avaliable for use in your program. These PIDFF controllers are not tied to any roll/pitch/yaw profiles or other controls.
The output of these controllers can be used in an IPF program by using the `Programming PID` operand.
The `<setpoint value>` of the controller is the target value for the controller to hit. The `<measurement value>` is the measurement of the current value. For instance, `<setpoint value>` could be the speed you want to go, and `<measurement value>` is the current speed.
P, I, D, and FF values will need to be manually adjusted to determine the appropriate value for the program and controller.

`pid <index> <enabled> <setpoint type> <setpoint value> <measurement type> <measurement value> <P gain> <I gain> <D gain> <FF gain>`

* `<index>` - ID of PID Controller, starting from `0`
Expand Down
36 changes: 33 additions & 3 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -1172,6 +1172,16 @@ S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer da

---

### frsky_use_legacy_gps_mode_sensor_ids

S.Port telemetry: If `ON`, send the legacy telemetry IDs for modes (Tmp1) and GNSS (Tmp2). These are old IDs, deprecated, and will be removed in INAV 10.0. Tools and scripts using these IDs should be updated to use the new IDs of **470** for Modes and **480** for GNSS. Default: 'OFF'

| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |

---

### fw_autotune_max_rate_deflection

The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`.
Expand Down Expand Up @@ -2004,7 +2014,7 @@ 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 with priority given to the selected sensor when the altitude error between the sensors exceeds a set limit. Only the selected sensor will be used in this case. 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 |
| --- | --- | --- |
Expand Down Expand Up @@ -2572,6 +2582,16 @@ Rate of the extra3 message for MAVLink telemetry

---

### mavlink_min_txbuffer

Minimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits.

| Default | Min | Max |
| --- | --- | --- |
| 33 | 0 | 100 |

---

### mavlink_pos_rate

Rate of the position message for MAVLink telemetry
Expand All @@ -2582,6 +2602,16 @@ Rate of the position message for MAVLink telemetry

---

### mavlink_radio_type

Mavlink radio type. Affects how RSSI and LQ are reported on OSD.

| Default | Min | Max |
| --- | --- | --- |
| GENERIC | | |

---

### mavlink_rc_chan_rate

Rate of the RC channels message for MAVLink telemetry
Expand Down Expand Up @@ -3704,7 +3734,7 @@ Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor onl

### nav_max_terrain_follow_alt

Max allowed above the ground altitude for terrain following mode
Max allowed above the ground altitude for terrain following mode [cm]

| Default | Min | Max |
| --- | --- | --- |
Expand Down Expand Up @@ -5044,7 +5074,7 @@ Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requ

### osd_radar_peers_display_time

Time in seconds to display next peer
Time in seconds to display next peer

| Default | Min | Max |
| --- | --- | --- |
Expand Down
8 changes: 6 additions & 2 deletions docs/Telemetry.md
Original file line number Diff line number Diff line change
Expand Up @@ -102,17 +102,21 @@ The following sensors are transmitted
* **VSpd** : vertical speed, unit is cm/s.
* **Hdg** : heading, North is 0°, South is 180°.
* **AccX,Y,Z** : accelerometer values (not sent if `frsky_pitch_roll = ON`).
* **Tmp1** : flight mode, sent as 5 digits. Number is sent as **ABCDE** detailed below. The numbers are additives (for example: if digit C is 6, it means both position hold and altitude hold are active) :
* **470** : flight mode, sent as 5 digits. Number is sent as **ABCDE** detailed below. The numbers are additives (for example: if digit C is 6, it means both position hold and altitude hold are active) :
* **A** : 1 = flaperon mode, 2 = auto tune mode, 4 = failsafe mode
* **B** : 1 = return to home, 2 = waypoint mode, 4 = headfree mode
* **C** : 1 = heading hold, 2 = altitude hold, 4 = position hold
* **D** : 1 = angle mode, 2 = horizon mode, 4 = passthru mode
* **E** : 1 = ok to arm, 2 = arming is prevented, 4 = armed
* **Tmp2** : GPS lock status, accuracy, home reset trigger, and number of satellites. Number is sent as **ABCD** detailed below. Typical minimum GPS 3D lock value is 3906 (GPS locked and home fixed, HDOP highest accuracy, 6 satellites).

_NOTE_ This sensor used to be **Tmp1**. The ID has been reassigned in INAV 8.0. The old ID of **Tmp1** can still be used, by using `set frsky_use_legacy_gps_mode_sensor_ids = ON`. This is deprecated and will be removed in INAV 10.0. All tools and scripts using the old IDs should be updated to use the new ID.
* **480** : GPS lock status, accuracy, home reset trigger, and number of satellites. Number is sent as **ABCD** detailed below. Typical minimum GPS 3D lock value is 3906 (GPS locked and home fixed, HDOP highest accuracy, 6 satellites).
* **A** : 1 = GPS fix, 2 = GPS home fix, 4 = home reset (numbers are additive)
* **B** : GPS accuracy based on HDOP (0 = lowest to 9 = highest accuracy)
* **C** : number of satellites locked (digit C & D are the number of locked satellites)
* **D** : number of satellites locked (if 14 satellites are locked, C = 1 & D = 4)

_NOTE_ This sensor used to be **Tmp2**. The ID has been reassigned in INAV 8.0. The old ID of **Tmp2** can still be used, by using `set frsky_use_legacy_gps_mode_sensor_ids = ON`. This is deprecated and will be removed in INAV 10.0. All tools and scripts using the old IDs should be updated to use the new ID.
* **GAlt** : GPS altitude, sea level is zero.
* **ASpd** : true air speed, from pitot sensor. This is _Knots * 10_
* **A4** : average cell value. Warning : unlike FLVSS and MLVSS sensors, you do not get actual lowest value of a cell, but an average : (total lipo voltage) / (number of cells)
Expand Down
32 changes: 32 additions & 0 deletions src/main/drivers/serial_uart_at32f43x.c
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,11 @@ 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),
#else
.af = GPIO_MUX_7,
#endif
#ifdef UART1_AHB1_PERIPHERALS
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
#endif
Expand All @@ -75,7 +79,11 @@ 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),
#else
.af = GPIO_MUX_7,
#endif
#ifdef UART2_AHB1_PERIPHERALS
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
#endif
Expand All @@ -96,7 +104,11 @@ 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),
#else
.af = GPIO_MUX_7,
#endif
#ifdef UART3_AHB1_PERIPHERALS
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
#endif
Expand All @@ -117,7 +129,11 @@ 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),
#else
.af = GPIO_MUX_8,
#endif
#ifdef UART4_AHB1_PERIPHERALS
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
#endif
Expand All @@ -138,7 +154,11 @@ 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),
#else
.af = GPIO_MUX_8,
#endif
#ifdef UART5_AHB1_PERIPHERALS
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
#endif
Expand All @@ -159,7 +179,11 @@ 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),
#else
.af = GPIO_MUX_8,
#endif
#ifdef UART6_AHB1_PERIPHERALS
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
#endif
Expand All @@ -180,7 +204,11 @@ 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),
#else
.af = GPIO_MUX_8,
#endif
.rcc_apb1 = RCC_APB1(UART7),
.irq = UART7_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART,
Expand All @@ -198,7 +226,11 @@ 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),
#else
.af = GPIO_MUX_8,
#endif
.rcc_apb1 = RCC_APB1(UART8),
.irq = UART8_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART,
Expand Down
11 changes: 11 additions & 0 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -3714,6 +3714,17 @@ static void cliSet(char *cmdline)
}

if (changeValue) {
// If changing the battery capacity unit, update the osd stats energy unit to match
if (strcmp(name, "battery_capacity_unit") == 0) {
if (batteryMetersConfig()->capacity_unit != (uint8_t)tmp.int_value) {
if (tmp.int_value == BAT_CAPACITY_UNIT_MAH) {
osdConfigMutable()->stats_energy_unit = OSD_STATS_ENERGY_UNIT_MAH;
} else {
osdConfigMutable()->stats_energy_unit = OSD_STATS_ENERGY_UNIT_WH;
}
}
}

cliSetIntFloatVar(val, tmp);

cliPrintf("%s set to ", name);
Expand Down
Loading

0 comments on commit e85c522

Please sign in to comment.