From a9177932481ab1358a5af6baae138b40b1862ae2 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 20 Aug 2021 11:36:45 -0400 Subject: [PATCH] mavlink: only block parameter sync until boot complete --- src/modules/mavlink/mavlink_main.h | 2 +- src/modules/mavlink/mavlink_receiver.cpp | 22 ++++++++++------------ 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 402c89d982..c3ba8344e2 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -417,7 +417,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 (_transmitting_enabled && _boot_complete && (!_wait_to_transmit || (_wait_to_transmit && _received_messages))); } + bool should_transmit() { return (_transmitting_enabled && (!_wait_to_transmit || (_wait_to_transmit && _received_messages))); } bool message_buffer_write(const void *ptr, int size); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index cf491674b6..c59852a05f 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3015,16 +3015,6 @@ MavlinkReceiver::run() px4_prctl(PR_SET_NAME, thread_name, px4_getpid()); } - // make sure mavlink app has booted before we start processing anything (parameter sync, etc) - while (!_mavlink->boot_complete()) { - if (hrt_elapsed_time(&_mavlink->get_first_start_time()) > 20_s) { - PX4_ERR("system boot did not complete in 20 seconds"); - _mavlink->set_boot_complete(); - } - - px4_usleep(100000); - } - // poll timeout in ms. Also defines the max update frequency of the mission & param manager, etc. const int timeout = 10; @@ -3136,9 +3126,17 @@ MavlinkReceiver::run() /* handle packet with mission manager */ _mission_manager.handle_message(&msg); - /* handle packet with parameter component */ - _parameters_manager.handle_message(&msg); + if (_mavlink->boot_complete()) { + // make sure mavlink app has booted before we start processing parameter sync + _parameters_manager.handle_message(&msg); + + } else { + if (hrt_elapsed_time(&_mavlink->get_first_start_time()) > 20_s) { + PX4_ERR("system boot did not complete in 20 seconds"); + _mavlink->set_boot_complete(); + } + } if (_mavlink->ftp_enabled()) { /* handle packet with ftp component */