From 38fd43ac2c6b7f8a102aad57b744743829094bf5 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 19 Feb 2021 07:32:40 -0800 Subject: [PATCH] Copter: change SRx_ docs value 1 50 --- ArduCopter/GCS_Mavlink.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index c3e83e6dbd..b59ca4ecdd 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -332,7 +332,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Raw sensor stream rate // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 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[0], 0), @@ -341,7 +341,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Extended status stream rate to ground station // @Description: Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_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[1], 0), @@ -350,7 +350,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 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], 0), @@ -359,7 +359,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Raw Control stream rate to ground station // @Description: Stream rate of RC_CHANNELS_SCALED (HIL only) 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], 0), @@ -368,7 +368,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @DisplayName: Position stream rate to ground station // @Description: Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0), @@ -377,7 +377,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, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0), @@ -386,7 +386,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[6], 0), @@ -395,7 +395,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, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station // @Units: Hz - // @Range: 0 10 + // @Range: 0 50 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0), @@ -404,7 +404,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[8], 0),