From 5b684e5e2b81237f031249495fc4ae8f6d3c3b81 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 19 Feb 2021 07:32:55 -0800 Subject: [PATCH] Sub: change SRx_ docs value 1 50 --- ArduSub/GCS_Mavlink.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index b55f393094..c89b288383 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -255,7 +255,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Raw sensor stream rate // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 0), @@ -264,7 +264,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extended status stream rate to ground station // @Description: Stream rate of SYS_STATUS, MEMINFO, MISSION_CURRENT, GPS_RAW_INT, NAV_CONTROLLER_OUTPUT, and LIMITS_STATUS to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 0), @@ -273,7 +273,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: RC Channel stream rate to ground station // @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS_RAW to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 0), @@ -282,7 +282,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Position stream rate to ground station // @Description: Stream rate of GLOBAL_POSITION_INT to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 0), @@ -291,7 +291,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extra data type 1 stream rate to ground station // @Description: Stream rate of ATTITUDE and SIMSTATE (SITL only) to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 0), @@ -300,7 +300,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extra data type 2 stream rate to ground station // @Description: Stream rate of VFR_HUD to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 0), @@ -309,7 +309,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extra data type 3 stream rate to ground station // @Description: Stream rate of AHRS, HWSTATUS, and SYSTEM_TIME to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 0), @@ -318,7 +318,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Parameter stream rate to ground station // @Description: Stream rate of PARAM_VALUE to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_PARAMS], 0),