From b9cd1ea7ed36084a23d0b80054711292dae38d71 Mon Sep 17 00:00:00 2001 From: a-maumau Date: Thu, 23 May 2024 16:02:23 +0900 Subject: [PATCH 1/6] remove unusing main func file Signed-off-by: a-maumau --- .../localization_error_monitor/src/main.cpp | 28 ------------------- 1 file changed, 28 deletions(-) delete mode 100644 localization/localization_error_monitor/src/main.cpp diff --git a/localization/localization_error_monitor/src/main.cpp b/localization/localization_error_monitor/src/main.cpp deleted file mode 100644 index f4fa5ab664005..0000000000000 --- a/localization/localization_error_monitor/src/main.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "localization_error_monitor/node.hpp" - -#include - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} From 9adc33b547250f48dc4a04c917b5ad367a7813fb Mon Sep 17 00:00:00 2001 From: a-maumau Date: Thu, 23 May 2024 16:05:46 +0900 Subject: [PATCH 2/6] add and mod to use glog Signed-off-by: a-maumau --- .../localization_error_monitor/CMakeLists.txt | 19 ++- .../localization_error_monitor.hpp | 64 ++++++++ .../localization_error_monitor.launch.xml | 2 +- .../localization_error_monitor/package.xml | 1 + .../src/localization_error_monitor.cpp | 149 ++++++++++++++++++ 5 files changed, 226 insertions(+), 9 deletions(-) create mode 100644 localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp create mode 100644 localization/localization_error_monitor/src/localization_error_monitor.cpp diff --git a/localization/localization_error_monitor/CMakeLists.txt b/localization/localization_error_monitor/CMakeLists.txt index 3528367486350..cacfb6bb26a12 100644 --- a/localization/localization_error_monitor/CMakeLists.txt +++ b/localization/localization_error_monitor/CMakeLists.txt @@ -4,15 +4,18 @@ project(localization_error_monitor) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(localization_error_monitor_module SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/diagnostics.cpp + src/localization_error_monitor.cpp ) -ament_auto_add_executable(localization_error_monitor - src/main.cpp - src/node.cpp +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "LocalizationErrorMonitor" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor ) -target_link_libraries(localization_error_monitor localization_error_monitor_module) + +ament_target_dependencies(${PROJECT_NAME}) if(BUILD_TESTING) function(add_testcase filepath) @@ -20,17 +23,17 @@ if(BUILD_TESTING) 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_link_libraries(${test_name} localization_error_monitor_module) + target_link_libraries(${test_name} ${PROJECT_NAME}) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() - find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() add_testcase(test/test_diagnostics.cpp) endif() -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE config launch ) diff --git a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp new file mode 100644 index 0000000000000..55037ab0001ce --- /dev/null +++ b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp @@ -0,0 +1,64 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LOCALIZATION_ERROR_MONITOR__NODE_HPP_ +#define LOCALIZATION_ERROR_MONITOR__NODE_HPP_ + +#include +#include +#include + +#include +#include +#include + +#include + +struct Ellipse +{ + double long_radius; + double short_radius; + double yaw; + Eigen::Matrix2d P; + double size_lateral_direction; +}; + +class LocalizationErrorMonitor : public rclcpp::Node +{ +private: + rclcpp::Subscription::SharedPtr odom_sub_; + rclcpp::Publisher::SharedPtr ellipse_marker_pub_; + rclcpp::Publisher::SharedPtr diag_pub_; + + rclcpp::TimerBase::SharedPtr timer_; + + std::unique_ptr logger_configure_; + + double scale_; + double error_ellipse_size_; + double warn_ellipse_size_; + double error_ellipse_size_lateral_direction_; + double warn_ellipse_size_lateral_direction_; + Ellipse ellipse_; + + void onOdom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg); + visualization_msgs::msg::Marker createEllipseMarker( + const Ellipse & ellipse, nav_msgs::msg::Odometry::ConstSharedPtr odom); + double measureSizeEllipseAlongBodyFrame(const Eigen::Matrix2d & Pinv, double theta); + +public: + explicit LocalizationErrorMonitor(const rclcpp::NodeOptions & options); + ~LocalizationErrorMonitor() = default; +}; +#endif // LOCALIZATION_ERROR_MONITOR__NODE_HPP_ diff --git a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml index eb2b5741b00fc..f901f6c2025ce 100644 --- a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml +++ b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/localization/localization_error_monitor/package.xml b/localization/localization_error_monitor/package.xml index a1b352d911a0d..0138451b069e4 100644 --- a/localization/localization_error_monitor/package.xml +++ b/localization/localization_error_monitor/package.xml @@ -23,6 +23,7 @@ diagnostic_msgs diagnostic_updater nav_msgs + rclcpp_components tf2 tf2_geometry_msgs tier4_autoware_utils diff --git a/localization/localization_error_monitor/src/localization_error_monitor.cpp b/localization/localization_error_monitor/src/localization_error_monitor.cpp new file mode 100644 index 0000000000000..67cdb78c942fb --- /dev/null +++ b/localization/localization_error_monitor/src/localization_error_monitor.cpp @@ -0,0 +1,149 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// 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/diagnostics.hpp" + +#include + +#include +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include +#include +#include +#include +#include +#include + +LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & options) +: Node("localization_error_monitor", options) +{ + scale_ = this->declare_parameter("scale"); + error_ellipse_size_ = this->declare_parameter("error_ellipse_size"); + warn_ellipse_size_ = this->declare_parameter("warn_ellipse_size"); + + error_ellipse_size_lateral_direction_ = + this->declare_parameter("error_ellipse_size_lateral_direction"); + warn_ellipse_size_lateral_direction_ = + this->declare_parameter("warn_ellipse_size_lateral_direction"); + + odom_sub_ = this->create_subscription( + "input/odom", 1, std::bind(&LocalizationErrorMonitor::onOdom, this, std::placeholders::_1)); + + // QoS setup + rclcpp::QoS durable_qos(1); + durable_qos.transient_local(); // option for latching + ellipse_marker_pub_ = + this->create_publisher("debug/ellipse_marker", durable_qos); + + diag_pub_ = this->create_publisher("/diagnostics", 10); + + logger_configure_ = std::make_unique(this); +} + +visualization_msgs::msg::Marker LocalizationErrorMonitor::createEllipseMarker( + const Ellipse & ellipse, nav_msgs::msg::Odometry::ConstSharedPtr odom) +{ + tf2::Quaternion quat; + quat.setEuler(0, 0, ellipse.yaw); + + const double ellipse_long_radius = std::min(ellipse.long_radius, 30.0); + const double ellipse_short_radius = std::min(ellipse.short_radius, 30.0); + visualization_msgs::msg::Marker marker; + marker.header = odom->header; + marker.header.stamp = this->now(); + marker.ns = "error_ellipse"; + marker.id = 0; + marker.type = visualization_msgs::msg::Marker::SPHERE; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.pose = odom->pose.pose; + marker.pose.orientation = tf2::toMsg(quat); + marker.scale.x = ellipse_long_radius * 2; + marker.scale.y = ellipse_short_radius * 2; + marker.scale.z = 0.01; + marker.color.a = 0.1; + marker.color.r = 0.0; + marker.color.g = 0.0; + marker.color.b = 1.0; + return marker; +} + +void LocalizationErrorMonitor::onOdom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg) +{ + // create xy covariance (2x2 matrix) + // input geometry_msgs::PoseWithCovariance contain 6x6 matrix + Eigen::Matrix2d xy_covariance; + const auto cov = input_msg->pose.covariance; + xy_covariance(0, 0) = cov[0 * 6 + 0]; + xy_covariance(0, 1) = cov[0 * 6 + 1]; + xy_covariance(1, 0) = cov[1 * 6 + 0]; + xy_covariance(1, 1) = cov[1 * 6 + 1]; + + Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); + + // eigen values and vectors are sorted in ascending order + ellipse_.long_radius = scale_ * std::sqrt(eigensolver.eigenvalues()(1)); + ellipse_.short_radius = scale_ * std::sqrt(eigensolver.eigenvalues()(0)); + + // principal component vector + const Eigen::Vector2d pc_vector = eigensolver.eigenvectors().col(1); + ellipse_.yaw = std::atan2(pc_vector.y(), pc_vector.x()); + + // ellipse size along lateral direction (body-frame) + 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); + + const auto ellipse_marker = createEllipseMarker(ellipse_, input_msg); + ellipse_marker_pub_->publish(ellipse_marker); + + // diagnostics + std::vector diag_status_array; + diag_status_array.push_back( + checkLocalizationAccuracy(ellipse_.long_radius, warn_ellipse_size_, error_ellipse_size_)); + diag_status_array.push_back(checkLocalizationAccuracyLateralDirection( + 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.name = "localization: " + std::string(this->get_name()); + diag_merged_status.hardware_id = this->get_name(); + + diagnostic_msgs::msg::DiagnosticArray diag_msg; + diag_msg.header.stamp = this->now(); + diag_msg.status.push_back(diag_merged_status); + diag_pub_->publish(diag_msg); +} + +double LocalizationErrorMonitor::measureSizeEllipseAlongBodyFrame( + const Eigen::Matrix2d & Pinv, const double theta) +{ + Eigen::MatrixXd e(2, 1); + e(0, 0) = std::cos(theta); + e(1, 0) = std::sin(theta); + + double d = std::sqrt((e.transpose() * Pinv * e)(0, 0) / Pinv.determinant()); + return d; +} + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(LocalizationErrorMonitor) From bd867da4a389017ca5b04ddf96e832705379141a Mon Sep 17 00:00:00 2001 From: a-maumau Date: Thu, 23 May 2024 16:07:00 +0900 Subject: [PATCH 3/6] change name to localization_error_monitor Signed-off-by: a-maumau --- .../localization_error_monitor/node.hpp | 64 -------- .../localization_error_monitor/src/node.cpp | 145 ------------------ 2 files changed, 209 deletions(-) delete mode 100644 localization/localization_error_monitor/include/localization_error_monitor/node.hpp delete mode 100644 localization/localization_error_monitor/src/node.cpp diff --git a/localization/localization_error_monitor/include/localization_error_monitor/node.hpp b/localization/localization_error_monitor/include/localization_error_monitor/node.hpp deleted file mode 100644 index 296b278004333..0000000000000 --- a/localization/localization_error_monitor/include/localization_error_monitor/node.hpp +++ /dev/null @@ -1,64 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef LOCALIZATION_ERROR_MONITOR__NODE_HPP_ -#define LOCALIZATION_ERROR_MONITOR__NODE_HPP_ - -#include -#include -#include - -#include -#include -#include - -#include - -struct Ellipse -{ - double long_radius; - double short_radius; - double yaw; - Eigen::Matrix2d P; - double size_lateral_direction; -}; - -class LocalizationErrorMonitor : public rclcpp::Node -{ -private: - rclcpp::Subscription::SharedPtr odom_sub_; - rclcpp::Publisher::SharedPtr ellipse_marker_pub_; - rclcpp::Publisher::SharedPtr diag_pub_; - - rclcpp::TimerBase::SharedPtr timer_; - - std::unique_ptr logger_configure_; - - double scale_; - double error_ellipse_size_; - double warn_ellipse_size_; - double error_ellipse_size_lateral_direction_; - double warn_ellipse_size_lateral_direction_; - Ellipse ellipse_; - - void onOdom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg); - visualization_msgs::msg::Marker createEllipseMarker( - const Ellipse & ellipse, nav_msgs::msg::Odometry::ConstSharedPtr odom); - double measureSizeEllipseAlongBodyFrame(const Eigen::Matrix2d & Pinv, double theta); - -public: - LocalizationErrorMonitor(); - ~LocalizationErrorMonitor() = default; -}; -#endif // LOCALIZATION_ERROR_MONITOR__NODE_HPP_ diff --git a/localization/localization_error_monitor/src/node.cpp b/localization/localization_error_monitor/src/node.cpp deleted file mode 100644 index f47372a0158b2..0000000000000 --- a/localization/localization_error_monitor/src/node.cpp +++ /dev/null @@ -1,145 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "localization_error_monitor/node.hpp" - -#include "localization_error_monitor/diagnostics.hpp" - -#include - -#include -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - -#include -#include -#include -#include -#include -#include - -LocalizationErrorMonitor::LocalizationErrorMonitor() : Node("localization_error_monitor") -{ - scale_ = this->declare_parameter("scale"); - error_ellipse_size_ = this->declare_parameter("error_ellipse_size"); - warn_ellipse_size_ = this->declare_parameter("warn_ellipse_size"); - - error_ellipse_size_lateral_direction_ = - this->declare_parameter("error_ellipse_size_lateral_direction"); - warn_ellipse_size_lateral_direction_ = - this->declare_parameter("warn_ellipse_size_lateral_direction"); - - odom_sub_ = this->create_subscription( - "input/odom", 1, std::bind(&LocalizationErrorMonitor::onOdom, this, std::placeholders::_1)); - - // QoS setup - rclcpp::QoS durable_qos(1); - durable_qos.transient_local(); // option for latching - ellipse_marker_pub_ = - this->create_publisher("debug/ellipse_marker", durable_qos); - - diag_pub_ = this->create_publisher("/diagnostics", 10); - - logger_configure_ = std::make_unique(this); -} - -visualization_msgs::msg::Marker LocalizationErrorMonitor::createEllipseMarker( - const Ellipse & ellipse, nav_msgs::msg::Odometry::ConstSharedPtr odom) -{ - tf2::Quaternion quat; - quat.setEuler(0, 0, ellipse.yaw); - - const double ellipse_long_radius = std::min(ellipse.long_radius, 30.0); - const double ellipse_short_radius = std::min(ellipse.short_radius, 30.0); - visualization_msgs::msg::Marker marker; - marker.header = odom->header; - marker.header.stamp = this->now(); - marker.ns = "error_ellipse"; - marker.id = 0; - marker.type = visualization_msgs::msg::Marker::SPHERE; - marker.action = visualization_msgs::msg::Marker::ADD; - marker.pose = odom->pose.pose; - marker.pose.orientation = tf2::toMsg(quat); - marker.scale.x = ellipse_long_radius * 2; - marker.scale.y = ellipse_short_radius * 2; - marker.scale.z = 0.01; - marker.color.a = 0.1; - marker.color.r = 0.0; - marker.color.g = 0.0; - marker.color.b = 1.0; - return marker; -} - -void LocalizationErrorMonitor::onOdom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg) -{ - // create xy covariance (2x2 matrix) - // input geometry_msgs::PoseWithCovariance contain 6x6 matrix - Eigen::Matrix2d xy_covariance; - const auto cov = input_msg->pose.covariance; - xy_covariance(0, 0) = cov[0 * 6 + 0]; - xy_covariance(0, 1) = cov[0 * 6 + 1]; - xy_covariance(1, 0) = cov[1 * 6 + 0]; - xy_covariance(1, 1) = cov[1 * 6 + 1]; - - Eigen::SelfAdjointEigenSolver eigensolver(xy_covariance); - - // eigen values and vectors are sorted in ascending order - ellipse_.long_radius = scale_ * std::sqrt(eigensolver.eigenvalues()(1)); - ellipse_.short_radius = scale_ * std::sqrt(eigensolver.eigenvalues()(0)); - - // principal component vector - const Eigen::Vector2d pc_vector = eigensolver.eigenvectors().col(1); - ellipse_.yaw = std::atan2(pc_vector.y(), pc_vector.x()); - - // ellipse size along lateral direction (body-frame) - 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); - - const auto ellipse_marker = createEllipseMarker(ellipse_, input_msg); - ellipse_marker_pub_->publish(ellipse_marker); - - // diagnostics - std::vector diag_status_array; - diag_status_array.push_back( - checkLocalizationAccuracy(ellipse_.long_radius, warn_ellipse_size_, error_ellipse_size_)); - diag_status_array.push_back(checkLocalizationAccuracyLateralDirection( - 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.name = "localization: " + std::string(this->get_name()); - diag_merged_status.hardware_id = this->get_name(); - - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); - diag_msg.status.push_back(diag_merged_status); - diag_pub_->publish(diag_msg); -} - -double LocalizationErrorMonitor::measureSizeEllipseAlongBodyFrame( - const Eigen::Matrix2d & Pinv, const double theta) -{ - Eigen::MatrixXd e(2, 1); - e(0, 0) = std::cos(theta); - e(1, 0) = std::sin(theta); - - double d = std::sqrt((e.transpose() * Pinv * e)(0, 0) / Pinv.determinant()); - return d; -} From cbac251ff987d79a5f9f73b8e53798c611b68e7a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 23 May 2024 07:12:00 +0000 Subject: [PATCH 4/6] style(pre-commit): autofix --- .../localization_error_monitor.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp index 55037ab0001ce..6016677d88136 100644 --- a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp +++ b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_ERROR_MONITOR__NODE_HPP_ -#define LOCALIZATION_ERROR_MONITOR__NODE_HPP_ +#ifndef LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_ +#define LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_ #include #include @@ -61,4 +61,4 @@ class LocalizationErrorMonitor : public rclcpp::Node explicit LocalizationErrorMonitor(const rclcpp::NodeOptions & options); ~LocalizationErrorMonitor() = default; }; -#endif // LOCALIZATION_ERROR_MONITOR__NODE_HPP_ +#endif // LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_ From c4847232f9f7dd47862bdec91c4cee896c8acd24 Mon Sep 17 00:00:00 2001 From: a-maumau Date: Thu, 23 May 2024 16:13:19 +0900 Subject: [PATCH 5/6] rm dependencies Signed-off-by: a-maumau --- localization/localization_error_monitor/CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/localization/localization_error_monitor/CMakeLists.txt b/localization/localization_error_monitor/CMakeLists.txt index cacfb6bb26a12..c27e51e6e0359 100644 --- a/localization/localization_error_monitor/CMakeLists.txt +++ b/localization/localization_error_monitor/CMakeLists.txt @@ -15,8 +15,6 @@ rclcpp_components_register_node(${PROJECT_NAME} EXECUTOR SingleThreadedExecutor ) -ament_target_dependencies(${PROJECT_NAME}) - if(BUILD_TESTING) function(add_testcase filepath) get_filename_component(filename ${filepath} NAME) From 258a593ce0ffd405226aa8663174b79c0c2f854b Mon Sep 17 00:00:00 2001 From: a-maumau Date: Fri, 24 May 2024 10:08:32 +0900 Subject: [PATCH 6/6] change log output from screen to both Signed-off-by: a-maumau --- .../launch/localization_error_monitor.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml index f901f6c2025ce..ad3e8beff92ab 100644 --- a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml +++ b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml @@ -2,7 +2,7 @@ - +