Skip to content
Snippets Groups Projects
Commit 7a0d4358 authored by Lorenz Meier's avatar Lorenz Meier
Browse files

MAVLink app: Only start transmitting when boot is complete (#4666)

parent 6fa446b4
No related branches found
No related tags found
No related merge requests found
......@@ -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;
}
......
......@@ -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);
......
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