Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove old modes and GNSS sensors from SmartPort telemetry #10362

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 0 additions & 10 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -1162,16 +1162,6 @@ 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
4 changes: 0 additions & 4 deletions docs/Telemetry.md
Original file line number Diff line number Diff line change
Expand Up @@ -108,15 +108,11 @@ The following sensors are transmitted
* **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

_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
4 changes: 0 additions & 4 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3052,10 +3052,6 @@ groups:
description: "S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
default_value: OFF
type: bool
- name: frsky_use_legacy_gps_mode_sensor_ids
description: "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_value: OFF
type: bool
- name: report_cell_voltage
description: "S.Port and IBUS telemetry: Send the average cell voltage if set to ON"
default_value: OFF
Expand Down
8 changes: 0 additions & 8 deletions src/main/telemetry/smartport.c
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,6 @@ enum
FSSP_DATAID_ACCX = 0x0700,
FSSP_DATAID_ACCY = 0x0710,
FSSP_DATAID_ACCZ = 0x0720,
FSSP_DATAID_LEGACY_MODES = 0x0400, // Deprecated. Should be removed in INAV 10.0
FSSP_DATAID_LEGACY_GNSS = 0x0410, // Deprecated. Should be removed in INAV 10.0
FSSP_DATAID_HOME_DIST = 0x0420,
FSSP_DATAID_GPS_ALT = 0x0820,
FSSP_DATAID_ASPD = 0x0A00,
Expand Down Expand Up @@ -543,19 +541,13 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
break;
case FSSP_DATAID_MODES:
{
if (telemetryConfig()->frsky_use_legacy_gps_mode_sensor_ids)
id = FSSP_DATAID_LEGACY_MODES;

smartPortSendPackage(id, frskyGetFlightMode());
*clearToSend = false;
break;
}
#ifdef USE_GPS
case FSSP_DATAID_GNSS:
{
if (telemetryConfig()->frsky_use_legacy_gps_mode_sensor_ids)
id = FSSP_DATAID_LEGACY_GNSS;

if (smartPortShouldSendGPSData()) {
smartPortSendPackage(id, frskyGetGPSState());
*clearToSend = false;
Expand Down
1 change: 0 additions & 1 deletion src/main/telemetry/telemetry.c
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.telemetry_switch = SETTING_TELEMETRY_SWITCH_DEFAULT,
.telemetry_inverted = SETTING_TELEMETRY_INVERTED_DEFAULT,
.frsky_pitch_roll = SETTING_FRSKY_PITCH_ROLL_DEFAULT,
.frsky_use_legacy_gps_mode_sensor_ids = SETTING_FRSKY_USE_LEGACY_GPS_MODE_SENSOR_IDS_DEFAULT,
.report_cell_voltage = SETTING_REPORT_CELL_VOLTAGE_DEFAULT,
.hottAlarmSoundInterval = SETTING_HOTT_ALARM_SOUND_INTERVAL_DEFAULT,
.halfDuplex = SETTING_TELEMETRY_HALFDUPLEX_DEFAULT,
Expand Down
1 change: 0 additions & 1 deletion src/main/telemetry/telemetry.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ typedef struct telemetryConfig_s {
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry.
uint8_t frsky_pitch_roll;
bool frsky_use_legacy_gps_mode_sensor_ids;
uint8_t report_cell_voltage;
uint8_t hottAlarmSoundInterval;
uint8_t halfDuplex;
Expand Down
Loading