Skip to content

Commit

Permalink
use tier4_autoware_utils::StopWatch
Browse files Browse the repository at this point in the history
Signed-off-by: ito-san <fumihito.ito@tier4.jp>
  • Loading branch information
ito-san committed May 23, 2022
1 parent fa9328a commit 8f02967
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class ProcessMonitor : public rclcpp::Node
rclcpp::TimerBase::SharedPtr timer_; //!< @brief timer to execute top command
std::string top_output_; //!< @brief output from top command
bool is_top_error_; //!< @brief flag if an error occurs
float elapsed_ms_; //!< @brief Execution time of top command
double elapsed_ms_; //!< @brief Execution time of top command
};

#endif // SYSTEM_MONITOR__PROCESS_MONITOR__PROCESS_MONITOR_HPP_
1 change: 1 addition & 0 deletions system/system_monitor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_external_api_msgs</depend>

<exec_depend>chrony</exec_depend>
Expand Down
10 changes: 6 additions & 4 deletions system/system_monitor/src/process_monitor/process_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@

#include "system_monitor/system_monitor_utility.hpp"

#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <fmt/format.h>

#include <memory>
Expand Down Expand Up @@ -304,8 +306,9 @@ void ProcessMonitor::onTimer()
{
is_top_error_ = false;

// Remember start time to measure elapsed time
const auto t_start = std::chrono::high_resolution_clock::now();
// Start to measure elapsed time
tier4_autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch;
stop_watch.tic("execution_time");

bp::ipstream is_err;
bp::ipstream is_out;
Expand All @@ -324,8 +327,7 @@ void ProcessMonitor::onTimer()
is_out >> os.rdbuf();
top_output_ = os.str();

const auto t_end = std::chrono::high_resolution_clock::now();
elapsed_ms_ = std::chrono::duration<float, std::milli>(t_end - t_start).count();
elapsed_ms_ = stop_watch.toc("execution_time");
}

#include <rclcpp_components/register_node_macro.hpp>
Expand Down

0 comments on commit 8f02967

Please sign in to comment.