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

refactor(localization_error_monitor)!: prefix package and namespace with autoware #8423

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
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ localization/autoware_twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier
localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp
localization/autoware_geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/gyro_odometer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/autoware_localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/ndt_scan_matcher/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/pose_estimator_arbiter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<launch>
<group>
<include file="$(find-pkg-share localization_error_monitor)/launch/localization_error_monitor.launch.xml">
<include file="$(find-pkg-share autoware_localization_error_monitor)/launch/localization_error_monitor.launch.xml">
<arg name="input/odom" value="/localization/kinematic_state"/>
<arg name="param_file" value="$(var localization_error_monitor_param_path)"/>
</include>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(localization_error_monitor)
project(autoware_localization_error_monitor)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -10,7 +10,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "LocalizationErrorMonitor"
PLUGIN "autoware::localization_error_monitor::LocalizationErrorMonitor"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)
Expand All @@ -20,7 +20,7 @@ if(BUILD_TESTING)
get_filename_component(filename ${filepath} NAME)
string(REGEX REPLACE ".cpp" "" test_name ${filename})
ament_add_gtest(${test_name} ${filepath})
target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include)
target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/src)
target_link_libraries(${test_name} ${PROJECT_NAME})
ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS})
endfunction()
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
# localization_error_monitor
# autoware_localization_error_monitor

## Purpose

<p align="center">
<img src="./media/diagnostics.png" width="400">
</p>

localization_error_monitor is a package for diagnosing localization errors by monitoring uncertainty of the localization results.
autoware_localization_error_monitor is a package for diagnosing localization errors by monitoring uncertainty of the localization results.
The package monitors the following two values:

- size of long radius of confidence ellipse
Expand All @@ -29,4 +29,4 @@ The package monitors the following two values:

## Parameters

{{ json_to_markdown("localization/localization_error_monitor/schema/localization_error_monitor.schema.json") }}
{{ json_to_markdown("localization/autoware_localization_error_monitor/schema/localization_error_monitor.schema.json") }}
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<arg name="input/odom" default="/localization/kinematic_state"/>
<arg name="param_file" default="$(find-pkg-share autoware_localization_error_monitor)/config/localization_error_monitor.param.yaml"/>

<node pkg="autoware_localization_error_monitor" exec="autoware_localization_error_monitor_node" output="both">
<remap from="input/odom" to="$(var input/odom)"/>
<param from="$(var param_file)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>localization_error_monitor</name>
<name>autoware_localization_error_monitor</name>
<version>0.1.0</version>
<description>ros node for monitoring localization error</description>
<maintainer email="yamato.ando@tier4.jp">Yamato Ando</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "diagnostics.hpp"

#include <diagnostic_msgs/msg/diagnostic_status.hpp>

#include <string>
#include <vector>

namespace autoware::localization_error_monitor
{
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size)
{
Expand Down Expand Up @@ -92,3 +96,4 @@ diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status(

return merged_stat;
}
} // namespace autoware::localization_error_monitor
Original file line number Diff line number Diff line change
Expand Up @@ -12,20 +12,23 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
#define LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
#ifndef DIAGNOSTICS_HPP_
#define DIAGNOSTICS_HPP_

#include <diagnostic_msgs/msg/diagnostic_status.hpp>

#include <string>
#include <vector>

namespace autoware::localization_error_monitor
{
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 check_localization_accuracy_lateral_direction(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size);

diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status(
const std::vector<diagnostic_msgs::msg::DiagnosticStatus> & stat_array);
} // namespace autoware::localization_error_monitor

#endif // LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
#endif // DIAGNOSTICS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "localization_error_monitor/localization_error_monitor.hpp"
#include "localization_error_monitor.hpp"

#include "localization_error_monitor/diagnostics.hpp"
#include "diagnostics.hpp"

#include <Eigen/Dense>

Expand All @@ -31,7 +31,10 @@
#include <memory>
#include <string>
#include <utility>
#include <vector>

namespace autoware::localization_error_monitor
{
LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & options)
: Node("localization_error_monitor", options)
{
Expand Down Expand Up @@ -84,6 +87,7 @@ void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr i
diag_msg.status.push_back(diag_merged_status);
diag_pub_->publish(diag_msg);
}
} // namespace autoware::localization_error_monitor

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(LocalizationErrorMonitor)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::localization_error_monitor::LocalizationErrorMonitor)
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
#define LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
#ifndef LOCALIZATION_ERROR_MONITOR_HPP_
#define LOCALIZATION_ERROR_MONITOR_HPP_

#include "localization_util/covariance_ellipse.hpp"

Expand All @@ -27,6 +27,8 @@

#include <memory>

namespace autoware::localization_error_monitor
{
class LocalizationErrorMonitor : public rclcpp::Node
{
private:
Expand All @@ -50,4 +52,6 @@ class LocalizationErrorMonitor : public rclcpp::Node
public:
explicit LocalizationErrorMonitor(const rclcpp::NodeOptions & options);
};
#endif // LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
} // namespace autoware::localization_error_monitor

#endif // LOCALIZATION_ERROR_MONITOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "localization_error_monitor/diagnostics.hpp"
#include "diagnostics.hpp"

#include <gtest/gtest.h>

Expand All @@ -24,23 +24,28 @@ TEST(TestLocalizationErrorMonitorDiagnostics, CheckLocalizationAccuracy)
const double error_ellipse_size = 1.0;

double ellipse_size = 0.0;
stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = autoware::localization_error_monitor::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 = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = autoware::localization_error_monitor::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 = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = autoware::localization_error_monitor::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 = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = autoware::localization_error_monitor::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 = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
stat = autoware::localization_error_monitor::check_localization_accuracy(
ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
}

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

double ellipse_size = 0.0;
stat = check_localization_accuracy_lateral_direction(
stat = autoware::localization_error_monitor::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 = check_localization_accuracy_lateral_direction(
stat = autoware::localization_error_monitor::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 = check_localization_accuracy_lateral_direction(
stat = autoware::localization_error_monitor::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 = check_localization_accuracy_lateral_direction(
stat = autoware::localization_error_monitor::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 = check_localization_accuracy_lateral_direction(
stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::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 = merge_diagnostic_status(stat_array);
merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1");
}

This file was deleted.

Loading