@@ -22,6 +22,9 @@ const struct AP_Param::GroupInfo *GCS::_chan_var_info[MAVLINK_COMM_NUM_BUFFERS];
22
22
23
23
// tradition has different vehicles use different default stream rates. This may not be the case forever, but for now we maintain this behaviour:
24
24
25
+ // Unified signing options across all vehicles
26
+ #define STANDARD_DEFAULT_STREAM_RATE_OPTIONS (SROption::MAVLINK2_SIGNING)
27
+
25
28
#ifndef AP_MAV_DEFAULT_STREAM_RATE_RAW_SENS
26
29
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
27
30
#define AP_MAV_DEFAULT_STREAM_RATE_RAW_SENS 2
@@ -34,6 +37,7 @@ const struct AP_Param::GroupInfo *GCS::_chan_var_info[MAVLINK_COMM_NUM_BUFFERS];
34
37
#define AP_MAV_DEFAULT_STREAM_RATE_EXTRA3 3
35
38
#define AP_MAV_DEFAULT_STREAM_RATE_PARAMS 0
36
39
#define AP_MAV_DEFAULT_STREAM_RATE_ADSB 0
40
+ #define AP_MAV_DEFAULT_STREAM_RATE_OPTIONS STANDARD_DEFAULT_STREAM_RATE_OPTIONS
37
41
#elif APM_BUILD_TYPE(APM_BUILD_AntennaTracker) || APM_BUILD_TYPE(APM_BUILD_Rover)
38
42
#define AP_MAV_DEFAULT_STREAM_RATE_RAW_SENS 1
39
43
#define AP_MAV_DEFAULT_STREAM_RATE_EXT_STAT 1
@@ -45,6 +49,7 @@ const struct AP_Param::GroupInfo *GCS::_chan_var_info[MAVLINK_COMM_NUM_BUFFERS];
45
49
#define AP_MAV_DEFAULT_STREAM_RATE_EXTRA3 1
46
50
#define AP_MAV_DEFAULT_STREAM_RATE_PARAMS 10
47
51
#define AP_MAV_DEFAULT_STREAM_RATE_ADSB 0
52
+ #define AP_MAV_DEFAULT_STREAM_RATE_OPTIONS STANDARD_DEFAULT_STREAM_RATE_OPTIONS
48
53
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
49
54
#define AP_MAV_DEFAULT_STREAM_RATE_RAW_SENS 1
50
55
#define AP_MAV_DEFAULT_STREAM_RATE_EXT_STAT 1
@@ -56,6 +61,7 @@ const struct AP_Param::GroupInfo *GCS::_chan_var_info[MAVLINK_COMM_NUM_BUFFERS];
56
61
#define AP_MAV_DEFAULT_STREAM_RATE_EXTRA3 1
57
62
#define AP_MAV_DEFAULT_STREAM_RATE_PARAMS 10
58
63
#define AP_MAV_DEFAULT_STREAM_RATE_ADSB 5
64
+ #define AP_MAV_DEFAULT_STREAM_RATE_OPTIONS STANDARD_DEFAULT_STREAM_RATE_OPTIONS
59
65
#elif APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Blimp) || APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_AP_Periph)
60
66
#define AP_MAV_DEFAULT_STREAM_RATE_RAW_SENS 0
61
67
#define AP_MAV_DEFAULT_STREAM_RATE_EXT_STAT 0
@@ -67,6 +73,7 @@ const struct AP_Param::GroupInfo *GCS::_chan_var_info[MAVLINK_COMM_NUM_BUFFERS];
67
73
#define AP_MAV_DEFAULT_STREAM_RATE_EXTRA3 0
68
74
#define AP_MAV_DEFAULT_STREAM_RATE_PARAMS 0
69
75
#define AP_MAV_DEFAULT_STREAM_RATE_ADSB 0
76
+ #define AP_MAV_DEFAULT_STREAM_RATE_OPTIONS STANDARD_DEFAULT_STREAM_RATE_OPTIONS
70
77
#elif APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
71
78
#define AP_MAV_DEFAULT_STREAM_RATE_RAW_SENS 0
72
79
#define AP_MAV_DEFAULT_STREAM_RATE_EXT_STAT 0
@@ -78,6 +85,7 @@ const struct AP_Param::GroupInfo *GCS::_chan_var_info[MAVLINK_COMM_NUM_BUFFERS];
78
85
#define AP_MAV_DEFAULT_STREAM_RATE_EXTRA3 0
79
86
#define AP_MAV_DEFAULT_STREAM_RATE_PARAMS 0
80
87
#define AP_MAV_DEFAULT_STREAM_RATE_ADSB 0
88
+ #define AP_MAV_DEFAULT_STREAM_RATE_OPTIONS STANDARD_DEFAULT_STREAM_RATE_OPTIONS
81
89
#else
82
90
#error Need to set streamrates
83
91
#endif // APM_BUILD_TYPE
@@ -202,6 +210,18 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
202
210
// @RebootRequired: True
203
211
// @User: Advanced
204
212
AP_GROUPINFO (" _ADSB" , 10 , GCS_MAVLINK, streamRates[GCS_MAVLINK::STREAM_ADSB], DRATE (GCS_MAVLINK::STREAM_ADSB)),
213
+
214
+ // ------------
215
+ // IMPORTANT: Add new stream rates *before* the _OPTIONS parameter.
216
+ // ------------
217
+
218
+ // @Param: _OPTIONS
219
+ // @DisplayName: Bitmask for configuring this telemetry channel
220
+ // @Description: Bitmask for configuring this telemetry channel. For having effect on all channels, set the relevant mask in all SRx_OPTIONS parameters. Keep in mind that part of the flags may require a reboot to take action.
221
+ // @RebootRequired: True
222
+ // @User: Standard
223
+ // @Bitmask: 0:Enable MavLink2 signing (Reboot required)
224
+ AP_GROUPINFO (" _OPTIONS" , 11 , GCS_MAVLINK, options, float (AP_MAV_DEFAULT_STREAM_RATE_OPTIONS)),
205
225
AP_GROUPEND
206
226
};
207
227
#undef DRATE
0 commit comments