mirror of https://github.com/ArduPilot/ardupilot
Sub: Don't send HWSTATUS by default
This commit is contained in:
parent
5c73cd581f
commit
e5a6e1133f
|
@ -311,7 +311,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, and SYSTEM_TIME to ground station
|
||||
// @Description: Stream rate of AHRS and SYSTEM_TIME to ground station
|
||||
// @Units: Hz
|
||||
// @Range: 0 50
|
||||
// @Increment: 1
|
||||
|
@ -373,7 +373,6 @@ static const ap_message STREAM_EXTRA2_msgs[] = {
|
|||
};
|
||||
static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
MSG_AHRS,
|
||||
MSG_HWSTATUS,
|
||||
MSG_SYSTEM_TIME,
|
||||
MSG_RANGEFINDER,
|
||||
MSG_DISTANCE_SENSOR,
|
||||
|
|
Loading…
Reference in New Issue