mirror of https://github.com/ArduPilot/ardupilot
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:
parent
0afc9bf724
commit
7c86ce4d81
|
@ -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
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue