From 7c86ce4d81aaff6e9ca59f29b5f26d8bf69a253a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 30 May 2018 20:43:57 +1000 Subject: [PATCH] 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. --- ArduCopter/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index e06be0f9c8..79a07fa21d 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -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 };