Skip to content

Commit

Permalink
refactor based on linter
Browse files Browse the repository at this point in the history
Signed-off-by: a-maumau <[email protected]>
  • Loading branch information
a-maumau committed Jun 7, 2024
1 parent 17aad93 commit 646e1eb
Show file tree
Hide file tree
Showing 5 changed files with 45 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include <string>
#include <vector>

diagnostic_msgs::msg::DiagnosticStatus checkLocalizationAccuracy(
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size);
diagnostic_msgs::msg::DiagnosticStatus checkLocalizationAccuracyLateralDirection(
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direction(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size);

diagnostic_msgs::msg::DiagnosticStatus mergeDiagnosticStatus(
diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status(
const std::vector<diagnostic_msgs::msg::DiagnosticStatus> & stat_array);

#endif // LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -52,13 +52,12 @@ class LocalizationErrorMonitor : public rclcpp::Node
double warn_ellipse_size_lateral_direction_;
Ellipse ellipse_;

void onOdom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg);
visualization_msgs::msg::Marker createEllipseMarker(
void on_odom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg);
visualization_msgs::msg::Marker create_ellipse_marker(
const Ellipse & ellipse, nav_msgs::msg::Odometry::ConstSharedPtr odom);
double measureSizeEllipseAlongBodyFrame(const Eigen::Matrix2d & Pinv, double theta);
static double measure_size_ellipse_along_body_frame(const Eigen::Matrix2d & Pinv, double theta);

public:
explicit LocalizationErrorMonitor(const rclcpp::NodeOptions & options);
~LocalizationErrorMonitor() = default;
};
#endif // LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
6 changes: 3 additions & 3 deletions localization/localization_error_monitor/src/diagnostics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <string>
#include <vector>

diagnostic_msgs::msg::DiagnosticStatus checkLocalizationAccuracy(
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size)
{
diagnostic_msgs::msg::DiagnosticStatus stat;
Expand All @@ -41,7 +41,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkLocalizationAccuracy(
return stat;
}

diagnostic_msgs::msg::DiagnosticStatus checkLocalizationAccuracyLateralDirection(
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direction(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size)
{
diagnostic_msgs::msg::DiagnosticStatus stat;
Expand All @@ -66,7 +66,7 @@ diagnostic_msgs::msg::DiagnosticStatus checkLocalizationAccuracyLateralDirection
}

// The highest level within the stat_array will be reflected in the merged_stat.
diagnostic_msgs::msg::DiagnosticStatus mergeDiagnosticStatus(
diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status(
const std::vector<diagnostic_msgs::msg::DiagnosticStatus> & stat_array)
{
diagnostic_msgs::msg::DiagnosticStatus merged_stat;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o
this->declare_parameter<double>("warn_ellipse_size_lateral_direction");

odom_sub_ = this->create_subscription<nav_msgs::msg::Odometry>(
"input/odom", 1, std::bind(&LocalizationErrorMonitor::onOdom, this, std::placeholders::_1));
"input/odom", 1, std::bind(&LocalizationErrorMonitor::on_odom, this, std::placeholders::_1));

// QoS setup
rclcpp::QoS durable_qos(1);
Expand All @@ -58,7 +58,7 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
}

visualization_msgs::msg::Marker LocalizationErrorMonitor::createEllipseMarker(
visualization_msgs::msg::Marker LocalizationErrorMonitor::create_ellipse_marker(
const Ellipse & ellipse, nav_msgs::msg::Odometry::ConstSharedPtr odom)
{
tf2::Quaternion quat;
Expand All @@ -85,7 +85,7 @@ visualization_msgs::msg::Marker LocalizationErrorMonitor::createEllipseMarker(
return marker;
}

void LocalizationErrorMonitor::onOdom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg)
void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg)
{
// create xy covariance (2x2 matrix)
// input geometry_msgs::PoseWithCovariance contain 6x6 matrix
Expand All @@ -110,21 +110,21 @@ void LocalizationErrorMonitor::onOdom(nav_msgs::msg::Odometry::ConstSharedPtr in
ellipse_.P = xy_covariance;
const double yaw_vehicle = tf2::getYaw(input_msg->pose.pose.orientation);
ellipse_.size_lateral_direction =
scale_ * measureSizeEllipseAlongBodyFrame(ellipse_.P.inverse(), yaw_vehicle);
scale_ * measure_size_ellipse_along_body_frame(ellipse_.P.inverse(), yaw_vehicle);

const auto ellipse_marker = createEllipseMarker(ellipse_, input_msg);
const auto ellipse_marker = create_ellipse_marker(ellipse_, input_msg);
ellipse_marker_pub_->publish(ellipse_marker);

// diagnostics
std::vector<diagnostic_msgs::msg::DiagnosticStatus> diag_status_array;
diag_status_array.push_back(
checkLocalizationAccuracy(ellipse_.long_radius, warn_ellipse_size_, error_ellipse_size_));
diag_status_array.push_back(checkLocalizationAccuracyLateralDirection(
check_localization_accuracy(ellipse_.long_radius, warn_ellipse_size_, error_ellipse_size_));
diag_status_array.push_back(check_localization_accuracy_lateral_direction(
ellipse_.size_lateral_direction, warn_ellipse_size_lateral_direction_,
error_ellipse_size_lateral_direction_));

diagnostic_msgs::msg::DiagnosticStatus diag_merged_status;
diag_merged_status = mergeDiagnosticStatus(diag_status_array);
diag_merged_status = merge_diagnostic_status(diag_status_array);
diag_merged_status.name = "localization: " + std::string(this->get_name());
diag_merged_status.hardware_id = this->get_name();

Expand All @@ -134,7 +134,7 @@ void LocalizationErrorMonitor::onOdom(nav_msgs::msg::Odometry::ConstSharedPtr in
diag_pub_->publish(diag_msg);
}

double LocalizationErrorMonitor::measureSizeEllipseAlongBodyFrame(
double LocalizationErrorMonitor::measure_size_ellipse_along_body_frame(
const Eigen::Matrix2d & Pinv, const double theta)
{
Eigen::MatrixXd e(2, 1);
Expand Down
49 changes: 27 additions & 22 deletions localization/localization_error_monitor/test/test_diagnostics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,23 +24,23 @@ TEST(TestLocalizationErrorMonitorDiagnostics, CheckLocalizationAccuracy)
const double error_ellipse_size = 1.0;

double ellipse_size = 0.0;
stat = checkLocalizationAccuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);

ellipse_size = 0.7;
stat = checkLocalizationAccuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);

ellipse_size = 0.8;
stat = checkLocalizationAccuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);

ellipse_size = 0.9;
stat = checkLocalizationAccuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);

ellipse_size = 1.0;
stat = checkLocalizationAccuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
}

Expand All @@ -52,28 +52,33 @@ TEST(TestLocalizationErrorMonitorDiagnostics, CheckLocalizationAccuracyLateralDi
const double error_ellipse_size = 0.3;

double ellipse_size = 0.0;
stat =
checkLocalizationAccuracyLateralDirection(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size
);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);

ellipse_size = 0.24;
stat =
checkLocalizationAccuracyLateralDirection(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size
);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);

ellipse_size = 0.25;
stat =
checkLocalizationAccuracyLateralDirection(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size
);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);

ellipse_size = 0.29;
stat =
checkLocalizationAccuracyLateralDirection(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size
);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);

ellipse_size = 0.3;
stat =
checkLocalizationAccuracyLateralDirection(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size
);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
}

Expand All @@ -86,55 +91,55 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "OK";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stat_array.at(1).message = "OK";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
EXPECT_EQ(merged_stat.message, "OK");

stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(0).message = "WARN0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stat_array.at(1).message = "OK";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
EXPECT_EQ(merged_stat.message, "WARN0");

stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stat_array.at(0).message = "OK";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(1).message = "WARN1";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
EXPECT_EQ(merged_stat.message, "WARN1");

stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(0).message = "WARN0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(1).message = "WARN1";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
EXPECT_EQ(merged_stat.message, "WARN0; WARN1");

stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stat_array.at(0).message = "OK";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(1).message = "ERROR1";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "ERROR1");

stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(0).message = "WARN0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(1).message = "ERROR1";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "WARN0; ERROR1");

stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(0).message = "ERROR0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(1).message = "ERROR1";
merged_stat = mergeDiagnosticStatus(stat_array);
merged_stat = merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1");
}

0 comments on commit 646e1eb

Please sign in to comment.