From be6f75302248c204a57d7e1f81f1b5d1ff2b656b Mon Sep 17 00:00:00 2001 From: Claudio Micheli <claudio@auterion.com> Date: Fri, 22 Mar 2019 18:52:04 +0100 Subject: [PATCH] Fixed CI errors. changed _print_msg_once into private class member. Signed-off-by: Claudio Micheli <claudio@auterion.com> --- src/modules/commander/Commander.cpp | 7 +++---- src/modules/commander/Commander.hpp | 3 ++- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index cab3998489..44de0f8f10 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -3834,7 +3834,6 @@ bool Commander::preflight_check(bool report) void Commander::data_link_check(bool &status_changed) { bool updated = false; - static bool print_msg_once = false; orb_check(_telemetry_status_sub, &updated); @@ -3968,9 +3967,9 @@ void Commander::data_link_check(bool &status_changed) //if avoidance never started if (_datalink_last_heartbeat_avoidance_system == 0 && hrt_elapsed_time(&_datalink_last_heartbeat_avoidance_system) > _oa_boot_timeout.get() * 1_s) { - if (!print_msg_once) { + if (!_print_msg_once) { mavlink_log_critical(&mavlink_log_pub, "Avoidance system not available!"); - print_msg_once = true; + _print_msg_once = true; } } @@ -3981,7 +3980,7 @@ void Commander::data_link_check(bool &status_changed) _avoidance_system_lost = true; mavlink_log_critical(&mavlink_log_pub, "Avoidance system lost"); status_flags.avoidance_system_valid = false; - print_msg_once = false; + _print_msg_once = false; } //if status changed diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 012cbd19b5..c0c8509fd6 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -187,7 +187,6 @@ private: hrt_abstime _datalink_last_heartbeat_avoidance_system{0}; bool _avoidance_system_lost{false}; - hrt_abstime _avoidance_system_not_started{0}; bool _avoidance_system_status_change{false}; uint8_t _datalink_last_status_avoidance_system{telemetry_status_s::MAV_STATE_UNINIT}; @@ -204,6 +203,8 @@ private: systemlib::Hysteresis _auto_disarm_landed{false}; systemlib::Hysteresis _auto_disarm_killed{false}; + bool _print_msg_once{false}; + // Subscriptions Subscription<estimator_status_s> _estimator_status_sub{ORB_ID(estimator_status)}; Subscription<mission_result_s> _mission_result_sub{ORB_ID(mission_result)}; -- GitLab