Skip to content

Commit d0c39d3

Browse files
authored
fix(autoware_processing_time_checker): fix bugprone-exception-escape (#9780)
* fix: bugprone-error Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp> * fix: cpplint Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp> --------- Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>
1 parent fe597e2 commit d0c39d3

File tree

1 file changed

+43
-36
lines changed

1 file changed

+43
-36
lines changed

system/autoware_processing_time_checker/src/processing_time_checker.cpp

+43-36
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <chrono>
2121
#include <filesystem>
2222
#include <fstream>
23+
#include <iostream>
2324
#include <string>
2425
#include <vector>
2526

@@ -103,45 +104,51 @@ ProcessingTimeChecker::~ProcessingTimeChecker()
103104
return;
104105
}
105106

106-
// generate json data
107-
nlohmann::json j;
108-
for (const auto & accumulator_iterator : processing_time_accumulator_map_) {
109-
const auto module_name = accumulator_iterator.first;
110-
const auto processing_time_accumulator = accumulator_iterator.second;
111-
j[module_name + "/min"] = processing_time_accumulator.min();
112-
j[module_name + "/max"] = processing_time_accumulator.max();
113-
j[module_name + "/mean"] = processing_time_accumulator.mean();
114-
j[module_name + "/count"] = processing_time_accumulator.count();
115-
j[module_name + "/description"] = "processing time of " + module_name + "[ms]";
116-
}
107+
try {
108+
// generate json data
109+
nlohmann::json j;
110+
for (const auto & accumulator_iterator : processing_time_accumulator_map_) {
111+
const auto module_name = accumulator_iterator.first;
112+
const auto processing_time_accumulator = accumulator_iterator.second;
113+
j[module_name + "/min"] = processing_time_accumulator.min();
114+
j[module_name + "/max"] = processing_time_accumulator.max();
115+
j[module_name + "/mean"] = processing_time_accumulator.mean();
116+
j[module_name + "/count"] = processing_time_accumulator.count();
117+
j[module_name + "/description"] = "processing time of " + module_name + "[ms]";
118+
}
117119

118-
// get output folder
119-
const std::string output_folder_str =
120-
rclcpp::get_logging_directory().string() + "/autoware_metrics";
121-
if (!std::filesystem::exists(output_folder_str)) {
122-
if (!std::filesystem::create_directories(output_folder_str)) {
123-
RCLCPP_ERROR(
124-
this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str());
125-
return;
120+
// get output folder
121+
const std::string output_folder_str =
122+
rclcpp::get_logging_directory().string() + "/autoware_metrics";
123+
if (!std::filesystem::exists(output_folder_str)) {
124+
if (!std::filesystem::create_directories(output_folder_str)) {
125+
RCLCPP_ERROR(
126+
this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str());
127+
return;
128+
}
126129
}
127-
}
128130

129-
// get time stamp
130-
std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now());
131-
std::tm * local_time = std::localtime(&now_time_t);
132-
std::ostringstream oss;
133-
oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S");
134-
std::string cur_time_str = oss.str();
135-
136-
// Write metrics .json to file
137-
const std::string output_file_str =
138-
output_folder_str + "/autoware_processing_time_checker-" + cur_time_str + ".json";
139-
std::ofstream f(output_file_str);
140-
if (f.is_open()) {
141-
f << j.dump(4);
142-
f.close();
143-
} else {
144-
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str());
131+
// get time stamp
132+
std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now());
133+
std::tm * local_time = std::localtime(&now_time_t);
134+
std::ostringstream oss;
135+
oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S");
136+
std::string cur_time_str = oss.str();
137+
138+
// Write metrics .json to file
139+
const std::string output_file_str =
140+
output_folder_str + "/autoware_processing_time_checker-" + cur_time_str + ".json";
141+
std::ofstream f(output_file_str);
142+
if (f.is_open()) {
143+
f << j.dump(4);
144+
f.close();
145+
} else {
146+
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str());
147+
}
148+
} catch (const std::exception & e) {
149+
std::cerr << "Exception in ProcessingTimeChecker: " << e.what() << std::endl;
150+
} catch (...) {
151+
std::cerr << "Unknown exception in ProcessingTimeChecker" << std::endl;
145152
}
146153
}
147154

0 commit comments

Comments
 (0)