Skip to content

Commit

Permalink
feat: delete onTimeout
Browse files Browse the repository at this point in the history
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com>
  • Loading branch information
TetsuKawa committed Apr 15, 2024
1 parent c240ff1 commit ab1d848
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 76 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -82,16 +82,6 @@ class MemMonitor : public rclcpp::Node
*/
void onTimer();

/**
* @brief Timeout callback function for executing checkUsage
*/
void onUsageTimeout();

/**
* @brief Timeout callback function for executing checkEcc
*/
void onEccTimeout();

/**
* @brief get human-readable output for memory size
* @param [in] str size with bytes
Expand All @@ -111,13 +101,11 @@ class MemMonitor : public rclcpp::Node
timer_; //!< @brief Timer to execute readUsage and edac-utils command
rclcpp::CallbackGroup::SharedPtr timer_callback_group_; //!< @brief Callback Group

rclcpp::TimerBase::SharedPtr timeout_timer_; //!< @brief Timer for executing readUsage
std::mutex usage_mutex_; //!< @brief Mutex for output from /proc/meminfo
std::string usage_error_str_; //!< @brief Error string
std::map<std::string, size_t> usage_map_; //!< @brief Output of /proc/meminfo
double usage_elapsed_ms_; //!< @brief Execution time of readUsage
std::mutex usage_timeout_mutex_; //!< @brief Mutex regarding timeout for executing readUsage
bool usage_timeout_expired_; //!< @brief Timeout for executing readUsage has expired or not

std::mutex ecc_mutex_; //!< @brief Mutex for output from edac-util command
std::string ecc_error_str_; //!< @brief Error string
Expand All @@ -126,7 +114,6 @@ class MemMonitor : public rclcpp::Node
double ecc_elapsed_ms_; //!< @brief Execution time of edac-util command
std::mutex
ecc_timeout_mutex_; //!< @brief Mutex regarding timeout for executing edac-util command
bool ecc_timeout_expired_; //!< @brief Timeout for executing edac-util command has expired or not
bool use_edac_util_; //!< @brief Available to use edac-util command or not

/**
Expand Down
78 changes: 15 additions & 63 deletions system/system_monitor/src/mem_monitor/mem_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@ MemMonitor::MemMonitor(const rclcpp::NodeOptions & options)
updater_(this),
available_size_(declare_parameter<int>("available_size", 1024) * 1024 * 1024),
usage_timeout_(declare_parameter<int>("usage_timeout", 5)),
usage_timeout_expired_(false),
ecc_timeout_(declare_parameter<int>("ecc_timeout", 5)),
ecc_timeout_expired_(false),
usage_elapsed_ms_(0.0),
ecc_elapsed_ms_(0.0),
use_edac_util_(false)
{
using namespace std::literals::chrono_literals;
Expand Down Expand Up @@ -87,7 +87,7 @@ void MemMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & stat)

// Check if Memory Usage is sound state
int level;
if (map["Mem: usage"] > map["Total: used+"]) {
if (map["Mem: total"] > map["Total: used+"]) {
level = DiagStatus::OK;
} else if (map["Mem: available"] >= available_size_) {
level = DiagStatus::WARN;
Expand All @@ -103,17 +103,12 @@ void MemMonitor::checkUsage(diagnostic_updater::DiagnosticStatusWrapper & stat)
}
}

// Check timeout has expired regarding executing readUsage
bool timeout_expired = false;
{
std::lock_guard<std::mutex> lock(usage_timeout_mutex_);
timeout_expired = usage_timeout_expired_;
}

if (!timeout_expired) {
stat.summary(level, usage_dict_.at(level));
} else {
if (elapsed_ms == 0.0) {
stat.summary(DiagStatus::WARN, "do not execute readUsage yet");
} else if (elapsed_ms > usage_timeout_ * 1000) {
stat.summary(DiagStatus::WARN, "readUsage timeout expired");
} else {
stat.summary(level, usage_dict_.at(level));
}

stat.addf("execution time", "%f ms", elapsed_ms);
Expand All @@ -124,7 +119,7 @@ void MemMonitor::checkEcc(diagnostic_updater::DiagnosticStatusWrapper & stat)
std::string error_str;
std::string pipe2_error_str;
std::string output;
double elapsed_ms;
double elapsed_ms = 0.0;

// thread-safe copy
{
Expand Down Expand Up @@ -164,17 +159,12 @@ void MemMonitor::checkEcc(diagnostic_updater::DiagnosticStatusWrapper & stat)
}
}

// Check timeout has expired regarding executing edac-util command
bool timeout_expired = false;
{
std::lock_guard<std::mutex> lock(ecc_timeout_mutex_);
timeout_expired = ecc_timeout_expired_;
}

if (!timeout_expired) {
stat.summary(DiagStatus::OK, "OK");
if (elapsed_ms == 0.0) {
stat.summary(DiagStatus::WARN, "do not execute edac-util yet");
} else if (elapsed_ms > ecc_timeout_ * 1000) {
stat.summary(DiagStatus::WARN, "edac-util timeout expired");
} else {
stat.summary(DiagStatus::WARN, "edac-util command timeout expired");
stat.summary(DiagStatus::OK, "OK");
}

stat.addf("execution time", "%f ms", elapsed_ms);
Expand Down Expand Up @@ -307,7 +297,7 @@ std::string MemMonitor::executeEdacUtil(std::string & output, std::string & pipe
}

void MemMonitor::onTimer()
{
{
tier4_autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch;

// Check Memory Usage
Expand All @@ -318,20 +308,8 @@ void MemMonitor::onTimer()
std::string error_str;
std::map<std::string, size_t> map;

// Start timeout timer for executing readUsage
{
std::lock_guard<std::mutex> lock(usage_timeout_mutex_);
usage_timeout_expired_ = false;
}
timeout_timer_ = rclcpp::create_timer(
this, get_clock(), std::chrono::seconds(usage_timeout_),
std::bind(&MemMonitor::onUsageTimeout, this));

error_str = readUsage(map);

// Returning from readUsage, stop timeout timer
timeout_timer_->cancel();

const double elapsed_ms = stop_watch.toc("usage_execution_time");

// thread-safe copy
Expand All @@ -351,20 +329,8 @@ void MemMonitor::onTimer()
std::string pipe2_error_str;
std::string output;

// Start timeout timer for executing edac-util command
{
std::lock_guard<std::mutex> lock(ecc_timeout_mutex_);
ecc_timeout_expired_ = false;
}
timeout_timer_ = rclcpp::create_timer(
this, get_clock(), std::chrono::seconds(ecc_timeout_),
std::bind(&MemMonitor::onEccTimeout, this));

error_str = executeEdacUtil(output, pipe2_error_str);

// Returning from edac-util command, stop timeout timer
timeout_timer_->cancel();

const double elapsed_ms = stop_watch.toc("ecc_execution_time");

// thread-safe copy
Expand All @@ -378,20 +344,6 @@ void MemMonitor::onTimer()
}
}

void MemMonitor::onUsageTimeout()
{
RCLCPP_WARN(get_logger(), "Read Memory Usage Timeout occurred.");
std::lock_guard<std::mutex> lock(usage_timeout_mutex_);
usage_timeout_expired_ = true;
}

void MemMonitor::onEccTimeout()
{
RCLCPP_WARN(get_logger(), "Execute edac-util Timeout occurred.");
std::lock_guard<std::mutex> lock(ecc_timeout_mutex_);
ecc_timeout_expired_ = true;
}

std::string MemMonitor::toHumanReadable(const std::string & str)
{
const char * units[] = {"B", "K", "M", "G", "T"};
Expand Down

0 comments on commit ab1d848

Please sign in to comment.