From ca80961a9279d3d01915af7ff0f50f47b1825e48 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 16 Oct 2022 18:00:46 -0500 Subject: [PATCH] ArduCopter: update SRX descriptions --- ArduCopter/GCS_Mavlink.cpp | 36 ++++++++++++++++++------------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 390c9cc080..640f3820a2 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -377,7 +377,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @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 + // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3 // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -386,8 +386,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0), // @Param: EXT_STAT - // @DisplayName: Extended status stream rate to ground station - // @Description: Stream rate of SYS_STATUS, POWER_STATUS, MCU_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 + // @DisplayName: Extended status stream rate + // @Description: MAVLink Stream rate of SYS_STATUS, POWER_STATUS, MCU_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW_INT (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, FENCE_STATUS, and GLOBAL_TARGET_POS_INT // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -396,8 +396,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0), // @Param: RC_CHAN - // @DisplayName: RC Channel stream rate to ground station - // @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station + // @DisplayName: RC Channel stream rate + // @Description: MAVLink Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -416,8 +416,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0), // @Param: POSITION - // @DisplayName: Position stream rate to ground station - // @Description: Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station + // @DisplayName: Position stream rate + // @Description: MAVLink Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -426,9 +426,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0), // @Param: EXTRA1 - // @DisplayName: Extra data type 1 stream rate to ground station - // @Description: Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2 and PID_TUNING to ground station - // @Units: Hz + // @DisplayName: Extra data type 1 stream rate + // @Description: MAVLink Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2 and PID_TUNING // @Range: 0 50 // @Increment: 1 // @RebootRequired: True @@ -436,8 +435,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0), // @Param: EXTRA2 - // @DisplayName: Extra data type 2 stream rate to ground station - // @Description: Stream rate of VFR_HUD to ground station + // @DisplayName: Extra data type 2 stream rate + // @Description: MAVLink Stream rate of VFR_HUD // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -446,8 +445,9 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0), // @Param: EXTRA3 - // @DisplayName: Extra data type 3 stream rate to ground station - // @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station + // @DisplayName: Extra data type 3 stream rate + // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY,GENERATOR_STATUS, and WINCH_STATUS + // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -456,8 +456,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0), // @Param: PARAMS - // @DisplayName: Parameter stream rate to ground station - // @Description: Stream rate of PARAM_VALUE to ground station + // @DisplayName: Parameter stream rate + // @Description: MAVLink Stream rate of PARAM_VALUE // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -466,8 +466,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0), // @Param: ADSB - // @DisplayName: ADSB stream rate to ground station - // @Description: ADSB stream rate to ground station + // @DisplayName: ADSB stream rate + // @Description: MAVLink ADSB stream rate // @Units: Hz // @Range: 0 50 // @Increment: 1