From 7a0d43586f7e11b669fb976b172b4d6761ec2611 Mon Sep 17 00:00:00 2001 From: Lorenz Meier <lorenz@px4.io> Date: Sat, 28 May 2016 09:57:07 +0200 Subject: [PATCH] MAVLink app: Only start transmitting when boot is complete (#4666) --- src/modules/mavlink/mavlink_main.cpp | 1 - src/modules/mavlink/mavlink_main.h | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 417975faab..42b7ba00e6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -912,7 +912,6 @@ Mavlink::send_bytes(const uint8_t *buf, unsigned packet_len) /* If the wait until transmit flag is on, only transmit after we've received messages. Otherwise, transmit all the time. */ if (!should_transmit()) { - warnx("not transmitting"); return; } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 6026acf793..2687cc2059 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -327,7 +327,7 @@ public: bool get_has_received_messages() { return _received_messages; } void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; } bool get_wait_to_transmit() { return _wait_to_transmit; } - bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); } + bool should_transmit() { return (_boot_complete && (!_wait_to_transmit || (_wait_to_transmit && _received_messages))); } bool message_buffer_write(const void *ptr, int size); -- GitLab