Skip to content

Commit 3b3545a

Browse files
committed
remove settings for system time, always send system time
1 parent 54629c2 commit 3b3545a

6 files changed

Lines changed: 0 additions & 21 deletions

File tree

docs/ADSB.md

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,6 @@ AT+SETTINGS=SAVE
6868
SoftRF needs more mavlink messages than other receivers, in INAV cli set correct mavlink output.
6969
```
7070
set mavlink_version = 1
71-
set mavlink_system_type_rate = 5
7271
set mavlink_pos_rate = 2
7372
save
7473
```

docs/Settings.md

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -2742,16 +2742,6 @@ MAVLink System ID
27422742

27432743
---
27442744

2745-
### mavlink_system_time_rate
2746-
2747-
Rate of the system time message for MAVLink telemetry
2748-
2749-
| Default | Min | Max |
2750-
| --- | --- | --- |
2751-
| 1 | 0 | 255 |
2752-
2753-
---
2754-
27552745
### mavlink_version
27562746

27572747
Version of MAVLink to use

src/main/fc/settings.yaml

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -3272,13 +3272,6 @@ groups:
32723272
min: 0
32733273
max: 255
32743274
default_value: 1
3275-
- name: mavlink_system_time_rate
3276-
description: "Rate of the system time message for MAVLink telemetry"
3277-
field: mavlink.system_time_rate
3278-
type: uint8_t
3279-
min: 0
3280-
max: 255
3281-
default_value: 1
32823275
- name: mavlink_version
32833276
field: mavlink.version
32843277
description: "Version of MAVLink to use"

src/main/telemetry/mavlink.c

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -332,7 +332,6 @@ static void configureMAVLinkStreamRates(void)
332332
mavRates[MAV_DATA_STREAM_EXTRA1] = telemetryConfig()->mavlink.extra1_rate;
333333
mavRates[MAV_DATA_STREAM_EXTRA2] = telemetryConfig()->mavlink.extra2_rate;
334334
mavRates[MAV_DATA_STREAM_EXTRA3] = telemetryConfig()->mavlink.extra3_rate;
335-
mavRates[MAV_DATA_STREAM_SYSTEM_TIME] = telemetryConfig()->mavlink.system_time_rate;
336335
}
337336

338337
void checkMAVLinkTelemetryState(void)

src/main/telemetry/telemetry.c

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
9494
.extra1_rate = SETTING_MAVLINK_EXTRA1_RATE_DEFAULT,
9595
.extra2_rate = SETTING_MAVLINK_EXTRA2_RATE_DEFAULT,
9696
.extra3_rate = SETTING_MAVLINK_EXTRA3_RATE_DEFAULT,
97-
.system_time_rate = SETTING_MAVLINK_SYSTEM_TIME_RATE_DEFAULT,
9897
.version = SETTING_MAVLINK_VERSION_DEFAULT,
9998
.min_txbuff = SETTING_MAVLINK_MIN_TXBUFFER_DEFAULT,
10099
.radio_type = SETTING_MAVLINK_RADIO_TYPE_DEFAULT,

src/main/telemetry/telemetry.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,6 @@ typedef struct telemetryConfig_s {
8484
uint8_t extra1_rate;
8585
uint8_t extra2_rate;
8686
uint8_t extra3_rate;
87-
uint8_t system_time_rate;
8887
uint8_t version;
8988
uint8_t min_txbuff;
9089
uint8_t radio_type;

0 commit comments

Comments
 (0)