Skip to content
Snippets Groups Projects
Commit 6b893a58 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

GCS_MAVLink: slow down parameter send a lot with no flow control

parent 63d0cddf
No related branches found
No related tags found
No related merge requests found
...@@ -129,6 +129,12 @@ GCS_MAVLINK::queued_param_send() ...@@ -129,6 +129,12 @@ GCS_MAVLINK::queued_param_send()
} }
count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES); count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES);
// when we don't have flow control we really need to keep the
// param download very slow, or it tends to stall
if (!have_flow_control() && count > 5) {
count = 5;
}
while (_queued_parameter != NULL && count--) { while (_queued_parameter != NULL && count--) {
AP_Param *vp; AP_Param *vp;
float value; float value;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment