Rover: update SRX descriptions

This commit is contained in:
Henry Wurzburg 2022-10-16 18:00:46 -05:00 committed by Peter Barker
parent 58f8c34211
commit 38a546a6c6
1 changed files with 18 additions and 18 deletions

View File

@ -408,7 +408,7 @@ void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mav
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
// @Param: RAW_SENS
// @DisplayName: Raw sensor stream rate
// @Description: Raw sensor stream rate 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
@ -417,8 +417,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),
// @Param: EXT_STAT
// @DisplayName: Extended status stream rate to ground station
// @Description: Extended status stream rate 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
@ -427,8 +427,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),
// @Param: RC_CHAN
// @DisplayName: RC Channel stream rate to ground station
// @Description: RC Channel stream rate 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
@ -437,8 +437,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),
// @Param: RAW_CTRL
// @DisplayName: Raw Control stream rate to ground station
// @Description: Raw Control stream rate to ground station
// @DisplayName: Raw Control stream rate
// @Description: MAVLink Raw Control stream rate of SERVO_OUT
// @Units: Hz
// @Range: 0 50
// @Increment: 1
@ -447,8 +447,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),
// @Param: POSITION
// @DisplayName: Position stream rate to ground station
// @Description: Position stream rate 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
@ -458,7 +458,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
// @Param: EXTRA1
// @DisplayName: Extra data type 1 stream rate to ground station
// @Description: Extra data type 1 stream rate to ground station
// @Description: MAVLink Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2 and PID_TUNING
// @Units: Hz
// @Range: 0 50
// @Increment: 1
@ -467,8 +467,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),
// @Param: EXTRA2
// @DisplayName: Extra data type 2 stream rate to ground station
// @Description: Extra data type 2 stream rate to ground station
// @DisplayName: Extra data type 2 stream rate
// @Description: MAVLink Stream rate of VFR_HUD
// @Units: Hz
// @Range: 0 50
// @Increment: 1
@ -477,8 +477,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),
// @Param: EXTRA3
// @DisplayName: Extra data type 3 stream rate to ground station
// @Description: Extra data type 3 stream rate to ground station
// @DisplayName: Extra data type 3 stream rate
// @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, BATTERY2, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY, and WHEEL_DISTANCE
// @Units: Hz
// @Range: 0 50
// @Increment: 1
@ -487,8 +487,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),
// @Param: PARAMS
// @DisplayName: Parameter stream rate to ground station
// @Description: Parameter stream rate to ground station
// @DisplayName: Parameter stream rate
// @Description: MAVLink Stream rate of PARAM_VALUE
// @Units: Hz
// @Range: 0 50
// @Increment: 1
@ -497,8 +497,8 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),
// @Param: ADSB
// @DisplayName: ADSB stream rate to ground station
// @Description: ADSB stream rate to ground station
// @DisplayName: ADSB stream rate
// @Description: MAVLink ADSB (AIS) stream rate
// @Units: Hz
// @Range: 0 50
// @Increment: 1