19
19
20
20
#include " system_monitor/ntp_monitor/ntp_monitor.hpp"
21
21
22
- #include " system_monitor/system_monitor_utility .hpp"
22
+ #include < tier4_autoware_utils/system/stop_watch .hpp>
23
23
24
24
#include < boost/filesystem.hpp>
25
25
#include < boost/process.hpp>
@@ -37,8 +37,12 @@ NTPMonitor::NTPMonitor(const rclcpp::NodeOptions & options)
37
37
: Node(" ntp_monitor" , options),
38
38
updater_(this ),
39
39
offset_warn_(declare_parameter<float >(" offset_warn" , 0.1 )),
40
- offset_error_(declare_parameter<float >(" offset_error" , 5.0 ))
40
+ offset_error_(declare_parameter<float >(" offset_error" , 5.0 )),
41
+ timeout_(declare_parameter<int >(" timeout" , 5 )),
42
+ timeout_expired_(false )
41
43
{
44
+ using namespace std ::literals::chrono_literals;
45
+
42
46
gethostname (hostname_, sizeof (hostname_));
43
47
44
48
// Check if command exists
@@ -47,18 +51,15 @@ NTPMonitor::NTPMonitor(const rclcpp::NodeOptions & options)
47
51
48
52
updater_.setHardwareID (hostname_);
49
53
updater_.add (" NTP Offset" , this , &NTPMonitor::checkOffset);
50
- }
51
54
52
- void NTPMonitor::update ()
53
- {
54
- updater_.force_update ();
55
+ // Start timer to execute top command
56
+ timer_callback_group_ = this ->create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
57
+ timer_ = rclcpp::create_timer (
58
+ this , get_clock (), 1s, std::bind (&NTPMonitor::onTimer, this ), timer_callback_group_);
55
59
}
56
60
57
61
void NTPMonitor::checkOffset (diagnostic_updater::DiagnosticStatusWrapper & stat)
58
62
{
59
- // Remember start time to measure elapsed time
60
- const auto t_start = SystemMonitorUtility::startMeasurement ();
61
-
62
63
if (!chronyc_exists_) {
63
64
stat.summary (DiagStatus::ERROR, " chronyc error" );
64
65
stat.add (
@@ -70,7 +71,18 @@ void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper & stat)
70
71
std::string pipe2_err_str;
71
72
float offset = 0 .0f ;
72
73
std::map<std::string, std::string> tracking_map;
73
- error_str = executeChronyc (offset, tracking_map, pipe2_err_str);
74
+ double elapsed_ms;
75
+
76
+ // thread-safe copy
77
+ {
78
+ std::lock_guard<std::mutex> lock (mutex_);
79
+ error_str = error_str_;
80
+ pipe2_err_str = pipe2_err_str_;
81
+ offset = offset_;
82
+ tracking_map = tracking_map_;
83
+ elapsed_ms = elapsed_ms_;
84
+ }
85
+
74
86
if (!pipe2_err_str.empty ()) {
75
87
stat.summary (DiagStatus::ERROR, " pipe2 error" );
76
88
stat.add (" pipe2" , pipe2_err_str);
@@ -94,10 +106,65 @@ void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper & stat)
94
106
for (auto itr = tracking_map.begin (); itr != tracking_map.end (); ++itr) {
95
107
stat.add (itr->first , itr->second );
96
108
}
97
- stat.summary (level, offset_dict_.at (level));
98
109
99
- // Measure elapsed time since start time and report
100
- SystemMonitorUtility::stopMeasurement (t_start, stat);
110
+ // Check timeout has expired regarding executing chronyc
111
+ bool timeout_expired = false ;
112
+ {
113
+ std::lock_guard<std::mutex> lock (timeout_mutex_);
114
+ timeout_expired = timeout_expired_;
115
+ }
116
+
117
+ if (!timeout_expired) {
118
+ stat.summary (level, offset_dict_.at (level));
119
+ } else {
120
+ stat.summary (DiagStatus::WARN, " chronyc timeout expired" );
121
+ }
122
+
123
+ stat.addf (" execution time" , " %f ms" , elapsed_ms);
124
+ }
125
+
126
+ void NTPMonitor::onTimer ()
127
+ {
128
+ // Start to measure elapsed time
129
+ tier4_autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch;
130
+ stop_watch.tic (" execution_time" );
131
+
132
+ std::string error_str;
133
+ std::string pipe2_err_str;
134
+ float offset = 0 .0f ;
135
+ std::map<std::string, std::string> tracking_map;
136
+
137
+ // Start timeout timer for executing chronyc
138
+ {
139
+ std::lock_guard<std::mutex> lock (timeout_mutex_);
140
+ timeout_expired_ = false ;
141
+ }
142
+ timeout_timer_ = rclcpp::create_timer (
143
+ this , get_clock (), std::chrono::seconds (timeout_), std::bind (&NTPMonitor::onTimeout, this ));
144
+
145
+ error_str = executeChronyc (offset, tracking_map, pipe2_err_str);
146
+
147
+ // Returning from chronyc, stop timeout timer
148
+ timeout_timer_->cancel ();
149
+
150
+ const double elapsed_ms = stop_watch.toc (" execution_time" );
151
+
152
+ // thread-safe copy
153
+ {
154
+ std::lock_guard<std::mutex> lock (mutex_);
155
+ error_str_ = error_str;
156
+ pipe2_err_str_ = pipe2_err_str;
157
+ offset_ = offset;
158
+ tracking_map_ = tracking_map;
159
+ elapsed_ms_ = elapsed_ms;
160
+ }
161
+ }
162
+
163
+ void NTPMonitor::onTimeout ()
164
+ {
165
+ RCLCPP_WARN (get_logger (), " Timeout occurred." );
166
+ std::lock_guard<std::mutex> lock (timeout_mutex_);
167
+ timeout_expired_ = true ;
101
168
}
102
169
103
170
std::string NTPMonitor::executeChronyc (
0 commit comments