mavlink: only warn once if broadcast fails

This fixes the issue where the console was spammed if a broadcast failed
after a connection had previously been established.
This commit is contained in:
Julian Oes
2016-07-13 09:55:58 +02:00
committed by Beat Küng
parent 399d4ef833
commit 3ed8b735c2
2 changed files with 8 additions and 1 deletions

View File

@@ -224,6 +224,7 @@ Mavlink::Mavlink() :
_src_addr_initialized(false),
_broadcast_address_found(false),
_broadcast_address_not_found_warned(false),
_broadcast_failed_warned(false),
_network_buf{},
_network_buf_len(0),
#endif
@@ -920,7 +921,12 @@ Mavlink::send_packet()
(struct sockaddr *)&_bcast_addr, sizeof(_bcast_addr));
if (bret <= 0) {
PX4_ERR("sending broadcast failed, errno: %d: %s", errno, strerror(errno));
if (!_broadcast_failed_warned) {
PX4_ERR("sending broadcast failed, errno: %d: %s", errno, strerror(errno));
_broadcast_failed_warned = true;
}
} else {
_broadcast_failed_warned = false;
}
}
}