mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Copter: Don't send HWSTATUS by default
This commit is contained in:
parent
dba90ec227
commit
5c73cd581f
@ -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,
|
||||
|
Loading…
Reference in New Issue
Block a user