From 5c8d3a87db976322219e23f905922f21962d82b4 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 19 Feb 2021 07:33:24 -0800 Subject: [PATCH] Plane: change SRx_ docs value 1 50 --- ArduPlane/GCS_Mavlink.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index ade326f0b2..411a7c2336 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -463,7 +463,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Raw sensor stream rate // @Description: Raw sensor stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1), @@ -472,7 +472,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extended status stream rate to ground station // @Description: Extended status stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1), @@ -481,7 +481,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: RC Channel stream rate to ground station // @Description: RC Channel stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1), @@ -490,7 +490,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Raw Control stream rate to ground station // @Description: Raw Control stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1), @@ -499,7 +499,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Position stream rate to ground station // @Description: Position stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1), @@ -508,7 +508,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extra data type 1 stream rate to ground station // @Description: Extra data type 1 stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1), @@ -517,7 +517,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extra data type 2 stream rate to ground station // @Description: Extra data type 2 stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1), @@ -526,7 +526,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extra data type 3 stream rate to ground station // @Description: Extra data type 3 stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1), @@ -535,7 +535,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Parameter stream rate to ground station // @Description: Parameter stream rate to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),