Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_planning_evaluator): fix bugprone-exception-escape #9730

Merged
merged 1 commit into from
Dec 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <chrono>
#include <filesystem>
#include <fstream>
#include <iostream>
#include <memory>
#include <string>
#include <vector>
Expand Down Expand Up @@ -50,47 +51,52 @@
if (!output_metrics_) {
return;
}

// generate json data
using json = nlohmann::json;
json j;
for (Metric metric : metrics_) {
const std::string base_name = metric_to_str.at(metric) + "/";
const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_);
if (stat) {
j[base_name + "min"] = stat->min();
j[base_name + "max"] = stat->max();
j[base_name + "mean"] = stat->mean();
try {
// generate json data
using json = nlohmann::json;
json j;
for (Metric metric : metrics_) {
const std::string base_name = metric_to_str.at(metric) + "/";
const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_);
if (stat) {
j[base_name + "min"] = stat->min();
j[base_name + "max"] = stat->max();
j[base_name + "mean"] = stat->mean();
}
}
}

// get output folder
const std::string output_folder_str =
rclcpp::get_logging_directory().string() + "/autoware_metrics";
if (!std::filesystem::exists(output_folder_str)) {
if (!std::filesystem::create_directories(output_folder_str)) {
RCLCPP_ERROR(
this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str());
return;
// get output folder
const std::string output_folder_str =
rclcpp::get_logging_directory().string() + "/autoware_metrics";
if (!std::filesystem::exists(output_folder_str)) {
if (!std::filesystem::create_directories(output_folder_str)) {
RCLCPP_ERROR(
this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str());
return;
}
}
}

// get time stamp
std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now());
std::tm * local_time = std::localtime(&now_time_t);
std::ostringstream oss;
oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S");
std::string cur_time_str = oss.str();

// Write metrics .json to file
const std::string output_file_str =
output_folder_str + "/autoware_motion_evaluator-" + cur_time_str + ".json";
std::ofstream f(output_file_str);
if (f.is_open()) {
f << j.dump(4);
f.close();
} else {
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str());
// get time stamp
std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now());
std::tm * local_time = std::localtime(&now_time_t);

Check warning on line 81 in evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp

View check run for this annotation

Codecov / codecov/patch

evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp#L80-L81

Added lines #L80 - L81 were not covered by tests
std::ostringstream oss;
oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S");
std::string cur_time_str = oss.str();

// Write metrics .json to file
const std::string output_file_str =
output_folder_str + "/autoware_motion_evaluator-" + cur_time_str + ".json";
std::ofstream f(output_file_str);
if (f.is_open()) {
f << j.dump(4);
f.close();
} else {
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str());
}
} catch (const std::exception & e) {
std::cerr << "Exception in MotionEvaluatorNode destructor: " << e.what() << std::endl;
} catch (...) {

Check warning on line 98 in evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp

View check run for this annotation

Codecov / codecov/patch

evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp#L97-L98

Added lines #L97 - L98 were not covered by tests
std::cerr << "Unknown exception in MotionEvaluatorNode destructor" << std::endl;

Check warning on line 99 in evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

~MotionEvaluatorNode has a cyclomatic complexity of 9, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}
}

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.38 to 4.54, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -25,6 +25,7 @@
#include <chrono>
#include <filesystem>
#include <fstream>
#include <iostream>
#include <limits>
#include <memory>
#include <string>
Expand Down Expand Up @@ -74,45 +75,51 @@
return;
}

// generate json data
using json = nlohmann::json;
json j;
for (Metric metric : metrics_) {
const std::string base_name = metric_to_str.at(metric) + "/";
j[base_name + "min"] = metric_accumulators_[static_cast<size_t>(metric)][0].min();
j[base_name + "max"] = metric_accumulators_[static_cast<size_t>(metric)][1].max();
j[base_name + "mean"] = metric_accumulators_[static_cast<size_t>(metric)][2].mean();
j[base_name + "count"] = metric_accumulators_[static_cast<size_t>(metric)][2].count();
j[base_name + "description"] = metric_descriptions.at(metric);
}
try {
// generate json data
using json = nlohmann::json;
json j;
for (Metric metric : metrics_) {
const std::string base_name = metric_to_str.at(metric) + "/";
j[base_name + "min"] = metric_accumulators_[static_cast<size_t>(metric)][0].min();
j[base_name + "max"] = metric_accumulators_[static_cast<size_t>(metric)][1].max();
j[base_name + "mean"] = metric_accumulators_[static_cast<size_t>(metric)][2].mean();
j[base_name + "count"] = metric_accumulators_[static_cast<size_t>(metric)][2].count();
j[base_name + "description"] = metric_descriptions.at(metric);
}

// get output folder
const std::string output_folder_str =
rclcpp::get_logging_directory().string() + "/autoware_metrics";
if (!std::filesystem::exists(output_folder_str)) {
if (!std::filesystem::create_directories(output_folder_str)) {
RCLCPP_ERROR(
this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str());
return;
// get output folder
const std::string output_folder_str =
rclcpp::get_logging_directory().string() + "/autoware_metrics";
if (!std::filesystem::exists(output_folder_str)) {
if (!std::filesystem::create_directories(output_folder_str)) {
RCLCPP_ERROR(
this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str());
return;
}
}
}

// get time stamp
std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now());
std::tm * local_time = std::localtime(&now_time_t);
std::ostringstream oss;
oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S");
std::string cur_time_str = oss.str();

// Write metrics .json to file
const std::string output_file_str =
output_folder_str + "/autoware_planning_evaluator-" + cur_time_str + ".json";
std::ofstream f(output_file_str);
if (f.is_open()) {
f << j.dump(4);
f.close();
} else {
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str());
// get time stamp
std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now());
std::tm * local_time = std::localtime(&now_time_t);

Check warning on line 104 in evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp

View check run for this annotation

Codecov / codecov/patch

evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp#L103-L104

Added lines #L103 - L104 were not covered by tests
std::ostringstream oss;
oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S");
std::string cur_time_str = oss.str();

// Write metrics .json to file
const std::string output_file_str =
output_folder_str + "/autoware_planning_evaluator-" + cur_time_str + ".json";
std::ofstream f(output_file_str);
if (f.is_open()) {
f << j.dump(4);
f.close();
} else {
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str());
}
} catch (const std::exception & e) {
std::cerr << "Exception in MotionEvaluatorNode destructor: " << e.what() << std::endl;
} catch (...) {

Check warning on line 121 in evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp

View check run for this annotation

Codecov / codecov/patch

evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp#L120-L121

Added lines #L120 - L121 were not covered by tests
std::cerr << "Unknown exception in MotionEvaluatorNode destructor" << std::endl;
}
}

Expand Down
Loading