From c80cd1daa57793d2cee55a42e5b65126425ffd08 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 20 Feb 2022 12:08:11 +1100 Subject: [PATCH] ArduCopter: add RebootRequred to stream rate parameters --- ArduCopter/GCS_Mavlink.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 12d88004a7..b02b1be879 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -380,6 +380,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], 0), @@ -389,6 +390,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], 0), @@ -398,6 +400,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], 0), @@ -407,6 +410,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], 0), @@ -416,6 +420,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], 0), @@ -425,6 +430,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], 0), @@ -434,6 +440,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], 0), @@ -443,6 +450,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], 0), @@ -452,6 +460,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], 0), @@ -461,6 +470,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0), AP_GROUPEND