diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 30ae53ed83..0f29d59ca5 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -217,6 +217,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0), @@ -226,6 +227,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0), @@ -235,6 +237,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0), @@ -244,6 +247,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0), @@ -253,6 +257,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0), @@ -262,6 +267,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0), @@ -271,6 +277,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0), @@ -280,6 +287,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0), @@ -289,6 +297,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0), AP_GROUPEND