Copter: change default streamrate for ADSB from 5 to 0

No other stream has a default streamrate in Copter.

This causes us small amounts of overhead as it marks all channels as
streaming.
This commit is contained in:
Peter Barker 2018-05-30 20:43:57 +10:00 committed by Randy Mackay
parent 0afc9bf724
commit 7c86ce4d81
1 changed files with 1 additions and 1 deletions

View File

@ -444,7 +444,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
// @Range: 0 50
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK, streamRates[9], 5),
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK, streamRates[9], 0),
AP_GROUPEND
};