mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-20 16:57:35 +08:00
mavlink: STATUSTEXT increase stale message timeout
This commit is contained in:
@@ -776,7 +776,7 @@ void Mavlink::send_finish()
|
||||
# endif // CONFIG_NET
|
||||
|
||||
if ((_mode != MAVLINK_MODE_ONBOARD) && broadcast_enabled() &&
|
||||
(!get_client_source_initialized() || !is_connected())) {
|
||||
(!get_client_source_initialized() || !is_gcs_connected())) {
|
||||
|
||||
if (!_broadcast_address_found) {
|
||||
find_broadcast_address();
|
||||
|
||||
@@ -281,7 +281,7 @@ public:
|
||||
|
||||
bool get_forwarding_on() { return _forwarding_on; }
|
||||
|
||||
bool is_connected() { return _tstatus.heartbeat_type_gcs; }
|
||||
bool is_gcs_connected() { return _tstatus.heartbeat_type_gcs; }
|
||||
|
||||
#if defined(MAVLINK_UDP)
|
||||
static Mavlink *get_instance_for_network_port(unsigned long port);
|
||||
|
||||
@@ -68,7 +68,7 @@ private:
|
||||
|
||||
bool send() override
|
||||
{
|
||||
if (_mavlink->is_connected()) {
|
||||
if (_mavlink->is_gcs_connected()) {
|
||||
while (_mavlink_log_sub.updated() && (_mavlink->get_free_tx_buf() >= get_size())) {
|
||||
|
||||
const unsigned last_generation = _mavlink_log_sub.get_last_generation();
|
||||
@@ -77,7 +77,7 @@ private:
|
||||
|
||||
if (_mavlink_log_sub.update(&mavlink_log)) {
|
||||
// don't send stale messages
|
||||
if (hrt_elapsed_time(&mavlink_log.timestamp) < 2_s) {
|
||||
if (hrt_elapsed_time(&mavlink_log.timestamp) < 5_s) {
|
||||
|
||||
if (_mavlink_log_sub.get_last_generation() != (last_generation + 1)) {
|
||||
perf_count(_missed_msg_count_perf);
|
||||
|
||||
Reference in New Issue
Block a user