Browse Source

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

sbg
Lorenz Meier 9 years ago
parent
commit
7a0d43586f
  1. 1
      src/modules/mavlink/mavlink_main.cpp
  2. 2
      src/modules/mavlink/mavlink_main.h

1
src/modules/mavlink/mavlink_main.cpp

@ -912,7 +912,6 @@ Mavlink::send_bytes(const uint8_t *buf, unsigned packet_len) @@ -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;
}

2
src/modules/mavlink/mavlink_main.h

@ -327,7 +327,7 @@ public: @@ -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);

Loading…
Cancel
Save