From 75045057b759e90ebbe1f30c5db5d8188129eaac Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 20 Feb 2022 12:08:10 +1100 Subject: [PATCH] AntennaTracker: add RebootRequred to stream rate parameters --- AntennaTracker/GCS_Mavlink.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 62ca06772f..7d17686564 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -179,6 +179,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1), @@ -188,6 +189,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1), @@ -197,6 +199,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1), @@ -206,6 +209,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1), @@ -215,6 +219,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1), @@ -224,6 +229,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1), @@ -233,6 +239,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1), @@ -242,6 +249,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1), @@ -251,6 +259,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10), AP_GROUPEND