mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
MAVLink app: Only start transmitting when boot is complete (#4666)
This commit is contained in:
@@ -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.
|
/* If the wait until transmit flag is on, only transmit after we've received messages.
|
||||||
Otherwise, transmit all the time. */
|
Otherwise, transmit all the time. */
|
||||||
if (!should_transmit()) {
|
if (!should_transmit()) {
|
||||||
warnx("not transmitting");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -327,7 +327,7 @@ public:
|
|||||||
bool get_has_received_messages() { return _received_messages; }
|
bool get_has_received_messages() { return _received_messages; }
|
||||||
void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
|
void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
|
||||||
bool get_wait_to_transmit() { return _wait_to_transmit; }
|
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);
|
bool message_buffer_write(const void *ptr, int size);
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user