Skip to content

Commit 05f8ad2

Browse files
ito-sanh-ohta
andauthored
fix(ntp_monitor): move chronyc command execution to a timer (#4634)
* fix(ntp_monitor): move chronyc command execution to a timer Signed-off-by: ito-san <fumihito.ito@tier4.jp> * add newly added parameter timeout to config --------- Signed-off-by: ito-san <fumihito.ito@tier4.jp> Co-authored-by: Hiroki OTA <hiroki.ota@tier4.jp>
1 parent 9a8a043 commit 05f8ad2

File tree

3 files changed

+104
-13
lines changed

3 files changed

+104
-13
lines changed

system/system_monitor/config/ntp_monitor.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -3,3 +3,4 @@
33
server: ntp.nict.jp
44
offset_warn: 0.1
55
offset_error: 5.0
6+
timeout: 5 # The chronyc execution timeout will trigger a warning when this timer expires.

system/system_monitor/include/system_monitor/ntp_monitor/ntp_monitor.hpp

+23
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,16 @@ class NTPMonitor : public rclcpp::Node
5353
void checkOffset(
5454
diagnostic_updater::DiagnosticStatusWrapper & stat); // NOLINT(runtime/references)
5555

56+
/**
57+
* @brief Timer callback to execute chronyc command
58+
*/
59+
void onTimer();
60+
61+
/**
62+
* @brief Timeout callback function for executing chronyc
63+
*/
64+
void onTimeout();
65+
5666
/**
5767
* @brief function to execute chronyc
5868
* @param [out] outOffset offset value of NTP time
@@ -71,6 +81,19 @@ class NTPMonitor : public rclcpp::Node
7181

7282
float offset_warn_; //!< @brief NTP offset(sec) to generate warning
7383
float offset_error_; //!< @brief NTP offset(sec) to generate error
84+
int timeout_; //!< @brief Timeout duration for executing chronyc
85+
86+
rclcpp::TimerBase::SharedPtr timer_; //!< @brief Timer to execute chronyc command
87+
rclcpp::CallbackGroup::SharedPtr timer_callback_group_; //!< @brief Callback Group
88+
std::mutex mutex_; //!< @brief Mutex for output from chronyc command
89+
std::string error_str_; //!< @brief Error string
90+
std::string pipe2_err_str_; //!< @brief Error string regarding pipe2 function call
91+
float offset_; //!< @brief Offset value of NTP time
92+
std::map<std::string, std::string> tracking_map_; //!< @brief Output of chronyc tracking
93+
double elapsed_ms_; //!< @brief Execution time of chronyc command
94+
rclcpp::TimerBase::SharedPtr timeout_timer_; //!< @brief Timeout for executing chronyc
95+
std::mutex timeout_mutex_; //!< @brief Mutex regarding timeout for executing chronyc
96+
bool timeout_expired_; //!< @brief Timeout for executing chronyc has expired or not
7497

7598
/**
7699
* @brief NTP offset status messages

system/system_monitor/src/ntp_monitor/ntp_monitor.cpp

+80-13
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
#include "system_monitor/ntp_monitor/ntp_monitor.hpp"
2121

22-
#include "system_monitor/system_monitor_utility.hpp"
22+
#include <tier4_autoware_utils/system/stop_watch.hpp>
2323

2424
#include <boost/filesystem.hpp>
2525
#include <boost/process.hpp>
@@ -37,8 +37,12 @@ NTPMonitor::NTPMonitor(const rclcpp::NodeOptions & options)
3737
: Node("ntp_monitor", options),
3838
updater_(this),
3939
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)
4143
{
44+
using namespace std::literals::chrono_literals;
45+
4246
gethostname(hostname_, sizeof(hostname_));
4347

4448
// Check if command exists
@@ -47,18 +51,15 @@ NTPMonitor::NTPMonitor(const rclcpp::NodeOptions & options)
4751

4852
updater_.setHardwareID(hostname_);
4953
updater_.add("NTP Offset", this, &NTPMonitor::checkOffset);
50-
}
5154

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_);
5559
}
5660

5761
void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper & stat)
5862
{
59-
// Remember start time to measure elapsed time
60-
const auto t_start = SystemMonitorUtility::startMeasurement();
61-
6263
if (!chronyc_exists_) {
6364
stat.summary(DiagStatus::ERROR, "chronyc error");
6465
stat.add(
@@ -70,7 +71,18 @@ void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper & stat)
7071
std::string pipe2_err_str;
7172
float offset = 0.0f;
7273
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+
7486
if (!pipe2_err_str.empty()) {
7587
stat.summary(DiagStatus::ERROR, "pipe2 error");
7688
stat.add("pipe2", pipe2_err_str);
@@ -94,10 +106,65 @@ void NTPMonitor::checkOffset(diagnostic_updater::DiagnosticStatusWrapper & stat)
94106
for (auto itr = tracking_map.begin(); itr != tracking_map.end(); ++itr) {
95107
stat.add(itr->first, itr->second);
96108
}
97-
stat.summary(level, offset_dict_.at(level));
98109

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;
101168
}
102169

103170
std::string NTPMonitor::executeChronyc(

0 commit comments

Comments
 (0)