From 5c73cd581f7cd69747e01b56cc18d7f66beeae72 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 12 Sep 2022 13:53:29 -0700 Subject: [PATCH] Copter: Don't send HWSTATUS by default --- ArduCopter/GCS_Mavlink.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 8ca9eaa3a6..10cb95fb3f 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -446,7 +446,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate to ground station - // @Description: Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station + // @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -518,7 +518,6 @@ static const ap_message STREAM_EXTRA2_msgs[] = { }; static const ap_message STREAM_EXTRA3_msgs[] = { MSG_AHRS, - MSG_HWSTATUS, MSG_SYSTEM_TIME, MSG_WIND, MSG_RANGEFINDER,