mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Blimp: Don't send HWSTATUS by default
This commit is contained in:
parent
e5a6e1133f
commit
1759dd6368
@ -283,7 +283,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
|||||||
|
|
||||||
// @Param: EXTRA3
|
// @Param: EXTRA3
|
||||||
// @DisplayName: Extra data type 3 stream rate to ground station
|
// @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
|
// @Units: Hz
|
||||||
// @Range: 0 10
|
// @Range: 0 10
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
@ -345,7 +345,6 @@ static const ap_message STREAM_EXTRA2_msgs[] = {
|
|||||||
};
|
};
|
||||||
static const ap_message STREAM_EXTRA3_msgs[] = {
|
static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||||
MSG_AHRS,
|
MSG_AHRS,
|
||||||
MSG_HWSTATUS,
|
|
||||||
MSG_SYSTEM_TIME,
|
MSG_SYSTEM_TIME,
|
||||||
MSG_WIND,
|
MSG_WIND,
|
||||||
MSG_RANGEFINDER,
|
MSG_RANGEFINDER,
|
||||||
|
Loading…
Reference in New Issue
Block a user