scenario_simulator_v2 C++ API
status_monitor.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef STATUS_MONITOR__STATUS_MONITOR_HPP_
16 #define STATUS_MONITOR__STATUS_MONITOR_HPP_
17 
18 #include <cerrno>
19 #include <chrono>
20 #include <filesystem>
21 #include <fstream>
22 #include <mutex>
23 #include <thread>
24 #include <unordered_map>
25 #include <utility>
26 
27 namespace common
28 {
30 {
31  struct Status
32  {
33  const std::string name;
34 
35  std::chrono::high_resolution_clock::time_point last_access;
36 
37  using duration =
38  decltype(std::chrono::high_resolution_clock::now() - std::chrono::high_resolution_clock::now());
39 
40  duration minimum_access_interval;
41 
42  duration maximum_access_interval;
43 
44  bool exited = false;
45 
46  template <typename Name>
47  explicit Status(Name && name)
48  : name(std::forward<decltype(name)>(name)),
49  last_access(std::chrono::high_resolution_clock::now()),
50  minimum_access_interval(duration::max()),
51  maximum_access_interval(duration::min())
52  {
53  }
54 
55  auto since_last_access() const
56  {
57  return std::chrono::high_resolution_clock::now() - last_access;
58  }
59 
60  auto good() const { return exited or since_last_access() < threshold; }
61 
62  explicit operator bool() const { return good(); }
63  };
64 
65  static inline std::ofstream file;
66 
67  static inline std::unordered_map<std::thread::id, Status> statuses;
68 
69  static inline std::thread watchdog;
70 
71  static inline std::atomic_bool terminating;
72 
73  static inline std::chrono::seconds threshold = std::chrono::seconds(10);
74 
75  static inline std::mutex mutex;
76 
77 public:
78  explicit StatusMonitor();
79 
81 
82  template <typename Name>
83  auto touch(Name && name)
84  {
85  auto lock = std::scoped_lock<std::mutex>(mutex);
86 
87  if (auto iter = statuses.find(std::this_thread::get_id()); iter != std::end(statuses)) {
88  [[maybe_unused]] auto && [id, status] = *iter;
89 
90  const auto now = std::chrono::high_resolution_clock::now();
91 
92  const auto this_access_interval = now - status.last_access;
93 
94  status.minimum_access_interval =
95  std::min<std::decay_t<decltype(status.minimum_access_interval)>>(
96  status.minimum_access_interval, this_access_interval);
97 
98  status.maximum_access_interval =
99  std::max<std::decay_t<decltype(status.maximum_access_interval)>>(
100  status.maximum_access_interval, this_access_interval);
101 
102  status.last_access = now;
103  } else {
104  statuses.emplace(std::this_thread::get_id(), std::forward<decltype(name)>(name));
105  }
106  }
107 
108  template <typename T>
110  {
111  std::reference_wrapper<T> target;
112 
113  T value;
114 
115  public:
116  template <typename... Ts>
117  static auto locked_exchange(Ts &&... xs) -> decltype(auto)
118  {
119  auto lock = std::scoped_lock<std::mutex>(mutex);
120  return std::exchange(std::forward<decltype(xs)>(xs)...);
121  }
122 
123  template <typename U>
124  explicit ScopedExchanger(T & x, U && y)
125  : target(x), value(locked_exchange(target.get(), std::forward<decltype(y)>(y)))
126  {
127  }
128 
129  ~ScopedExchanger() { locked_exchange(target.get(), value); }
130  };
131 
132  template <typename Thunk>
133  auto overrideThreshold(const std::chrono::seconds & t, Thunk thunk) -> decltype(auto)
134  {
135  auto exchanger = ScopedExchanger(threshold, t);
136 
137  return thunk();
138  }
139 
140  auto write() const -> void;
141 } static status_monitor;
142 } // namespace common
143 
144 #endif // STATUS_MONITOR__STATUS_MONITOR_HPP_
Definition: status_monitor.hpp:110
ScopedExchanger(T &x, U &&y)
Definition: status_monitor.hpp:124
static auto locked_exchange(Ts &&... xs) -> decltype(auto)
Definition: status_monitor.hpp:117
~ScopedExchanger()
Definition: status_monitor.hpp:129
Definition: status_monitor.hpp:30
auto write() const -> void
Definition: status_monitor.cpp:80
~StatusMonitor()
Definition: status_monitor.cpp:59
auto overrideThreshold(const std::chrono::seconds &t, Thunk thunk) -> decltype(auto)
Definition: status_monitor.hpp:133
auto touch(Name &&name)
Definition: status_monitor.hpp:83
StatusMonitor()
Definition: status_monitor.cpp:38
Definition: concatenate.hpp:24
class common::StatusMonitor status_monitor
Definition: cache.hpp:27
Status
Definition: job.hpp:34
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26