From 06b15a54e44d3731576282648cbdd373f817d90b Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 26 May 2023 11:06:33 +0900 Subject: [PATCH] feat(particle_initializer): merge particle_initializer into mpf (#52) * feat(particle_initializer): merge particle_initializer to modulalized_particle_filter Signed-off-by: kminoda * remove particle_initializer * remove debug message Signed-off-by: kminoda * remove related parts Signed-off-by: kminoda * update readme Signed-off-by: kminoda * rename publishing topic Signed-off-by: Kento Yabuuchi --------- Signed-off-by: kminoda Signed-off-by: Kento Yabuuchi Co-authored-by: Kento Yabuuchi --- .../particle_initializer/CMakeLists.txt | 32 ----- .../config/particle_initializer.param.yaml | 3 - .../particle_initializer.hpp | 46 ------- .../particle_initializer/package.xml | 27 ---- .../src/particle_initializer_core.cpp | 117 ------------------ .../src/particle_initializer_node.cpp | 24 ---- .../modularized_particle_filter/README.md | 17 +-- .../config/predictor.param.yaml | 4 +- .../prediction/predictor.hpp | 11 ++ .../src/prediction/predictor.cpp | 87 ++++++++++++- .../launch/impl/initializer.launch.xml | 7 -- .../yabloc_launch/launch/impl/pf.launch.xml | 2 +- .../yabloc_launch/launch/yabloc.launch.xml | 1 - .../launch/yabloc_multi_camera.launch.xml | 1 - localization/yabloc/yabloc_launch/package.xml | 1 - 15 files changed, 109 insertions(+), 271 deletions(-) delete mode 100644 localization/yabloc/initializer/particle_initializer/CMakeLists.txt delete mode 100644 localization/yabloc/initializer/particle_initializer/config/particle_initializer.param.yaml delete mode 100644 localization/yabloc/initializer/particle_initializer/include/particle_initializer/particle_initializer.hpp delete mode 100644 localization/yabloc/initializer/particle_initializer/package.xml delete mode 100644 localization/yabloc/initializer/particle_initializer/src/particle_initializer_core.cpp delete mode 100644 localization/yabloc/initializer/particle_initializer/src/particle_initializer_node.cpp diff --git a/localization/yabloc/initializer/particle_initializer/CMakeLists.txt b/localization/yabloc/initializer/particle_initializer/CMakeLists.txt deleted file mode 100644 index bcf2970e8f132..0000000000000 --- a/localization/yabloc/initializer/particle_initializer/CMakeLists.txt +++ /dev/null @@ -1,32 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(particle_initializer) - -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_EXTENSIONS OFF) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic -Werror) -endif() - -# =================================================== -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -# =================================================== -# Eigen3 -find_package(Eigen3 REQUIRED) - -# =================================================== -# Executable -set(TARGET particle_initializer_node) -ament_auto_add_executable(${TARGET} - src/particle_initializer_core.cpp - src/particle_initializer_node.cpp) -target_include_directories(${TARGET} PUBLIC include) -target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS}) - -# =================================================== -ament_auto_package(INSTALL_TO_SHARE config) \ No newline at end of file diff --git a/localization/yabloc/initializer/particle_initializer/config/particle_initializer.param.yaml b/localization/yabloc/initializer/particle_initializer/config/particle_initializer.param.yaml deleted file mode 100644 index c4878c6a36e48..0000000000000 --- a/localization/yabloc/initializer/particle_initializer/config/particle_initializer.param.yaml +++ /dev/null @@ -1,3 +0,0 @@ -/**: - ros__parameters: - cov_xx_yy: [2.0,0.25] \ No newline at end of file diff --git a/localization/yabloc/initializer/particle_initializer/include/particle_initializer/particle_initializer.hpp b/localization/yabloc/initializer/particle_initializer/include/particle_initializer/particle_initializer.hpp deleted file mode 100644 index e19281ad0f383..0000000000000 --- a/localization/yabloc/initializer/particle_initializer/include/particle_initializer/particle_initializer.hpp +++ /dev/null @@ -1,46 +0,0 @@ -// Copyright 2023 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. - -#pragma once -#include -#include - -#include -#include - -namespace yabloc::modularized_particle_filter -{ -class ParticleInitializer : public rclcpp::Node -{ -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - using PoseCovStamped = geometry_msgs::msg::PoseWithCovarianceStamped; - using Marker = visualization_msgs::msg::Marker; - - ParticleInitializer(); - -private: - const std::vector cov_xx_yy_; - rclcpp::Subscription::SharedPtr sub_initialpose_; - rclcpp::Publisher::SharedPtr pub_initialpose_; - rclcpp::Publisher::SharedPtr pub_marker_; - - void on_initial_pose(const PoseCovStamped & initialpose); - - void publish_range_marker(const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent); - PoseCovStamped rectify_initial_pose( - const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent, - const PoseCovStamped & raw_initialpose); -}; -} // namespace yabloc::modularized_particle_filter \ No newline at end of file diff --git a/localization/yabloc/initializer/particle_initializer/package.xml b/localization/yabloc/initializer/particle_initializer/package.xml deleted file mode 100644 index e19e0d22f6329..0000000000000 --- a/localization/yabloc/initializer/particle_initializer/package.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - particle_initializer - 0.0.0 - The particle filter initializer - Kento Yabuuchi - Apache License 2.0 - - ament_cmake_ros - - rclcpp - tf2 - std_msgs - std_srvs - geometry_msgs - sensor_msgs - visualization_msgs - - modularized_particle_filter - yabloc_common - ll2_decomposer - - - ament_cmake - - diff --git a/localization/yabloc/initializer/particle_initializer/src/particle_initializer_core.cpp b/localization/yabloc/initializer/particle_initializer/src/particle_initializer_core.cpp deleted file mode 100644 index ec5c85d4fafc6..0000000000000 --- a/localization/yabloc/initializer/particle_initializer/src/particle_initializer_core.cpp +++ /dev/null @@ -1,117 +0,0 @@ -// Copyright 2023 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 "particle_initializer/particle_initializer.hpp" - -namespace yabloc::modularized_particle_filter -{ -ParticleInitializer::ParticleInitializer() -: Node("particle_initializer"), - cov_xx_yy_{this->template declare_parameter>("cov_xx_yy")} -{ - using std::placeholders::_1; - - // Publisher - pub_initialpose_ = create_publisher("rectified/initialpose", 10); - pub_marker_ = create_publisher("init/marker", 10); - - // Subscriber - auto on_initial_pose = std::bind(&ParticleInitializer::on_initial_pose, this, _1); - sub_initialpose_ = - create_subscription("initialpose3d", 10, std::move(on_initial_pose)); -} - -void ParticleInitializer::on_initial_pose(const PoseCovStamped & initialpose) -{ - auto position = initialpose.pose.pose.position; - Eigen::Vector3f pos_vec3f; - pos_vec3f << position.x, position.y, position.z; - - auto orientation = initialpose.pose.pose.orientation; - float theta = 2 * std::atan2(orientation.z, orientation.w); - Eigen::Vector3f tangent; - tangent << std::cos(theta), std::sin(theta), 0; - - publish_range_marker(pos_vec3f, tangent); - - pub_initialpose_->publish(rectify_initial_pose(pos_vec3f, tangent, initialpose)); -} - -void ParticleInitializer::publish_range_marker( - const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent) -{ - Marker msg; - msg.type = Marker::LINE_STRIP; - msg.header.stamp = get_clock()->now(); - msg.header.frame_id = "map"; - msg.scale.x = 0.2; - msg.scale.y = 0.2; - - msg.color.r = 0; - msg.color.g = 1; - msg.color.b = 0; - msg.color.a = 1; - - auto cast2gp = [](const Eigen::Vector3f & vec3f) -> geometry_msgs::msg::Point { - geometry_msgs::msg::Point p; - p.x = vec3f.x(); - p.y = vec3f.y(); - p.z = vec3f.z(); - return p; - }; - - Eigen::Vector3f binormal; - binormal << -tangent.y(), tangent.x(), tangent.z(); - - msg.points.push_back(cast2gp(pos + tangent + binormal)); - msg.points.push_back(cast2gp(pos + tangent - binormal)); - msg.points.push_back(cast2gp(pos - tangent - binormal)); - msg.points.push_back(cast2gp(pos - tangent + binormal)); - msg.points.push_back(cast2gp(pos + tangent + binormal)); - - pub_marker_->publish(msg); -} - -ParticleInitializer::PoseCovStamped ParticleInitializer::rectify_initial_pose( - const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent, - const PoseCovStamped & raw_initialpose) -{ - PoseCovStamped msg = raw_initialpose; - msg.header.frame_id = "map"; - msg.pose.pose.position.x = pos.x(); - msg.pose.pose.position.y = pos.y(); - msg.pose.pose.position.z = pos.z(); - - float theta = std::atan2(tangent.y(), tangent.x()); - - msg.pose.pose.orientation.w = std::cos(theta / 2); - msg.pose.pose.orientation.x = 0; - msg.pose.pose.orientation.y = 0; - msg.pose.pose.orientation.z = std::sin(theta / 2); - - Eigen::Matrix2f cov; - cov << cov_xx_yy_.at(0), 0, 0, cov_xx_yy_.at(1); - Eigen::Rotation2D r(theta); - cov = r * cov * r.inverse(); - - msg.pose.covariance.at(6 * 0 + 0) = cov(0, 0); - msg.pose.covariance.at(6 * 0 + 1) = cov(0, 1); - msg.pose.covariance.at(6 * 1 + 0) = cov(1, 0); - msg.pose.covariance.at(6 * 1 + 1) = cov(1, 1); - msg.pose.covariance.at(6 * 5 + 5) = 0.0076; // 0.0076 = (5deg)^2 - - return msg; -} - -} // namespace yabloc::modularized_particle_filter \ No newline at end of file diff --git a/localization/yabloc/initializer/particle_initializer/src/particle_initializer_node.cpp b/localization/yabloc/initializer/particle_initializer/src/particle_initializer_node.cpp deleted file mode 100644 index f212b2eabad9d..0000000000000 --- a/localization/yabloc/initializer/particle_initializer/src/particle_initializer_node.cpp +++ /dev/null @@ -1,24 +0,0 @@ -// Copyright 2023 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 "particle_initializer/particle_initializer.hpp" - -int main(int argc, char * argv[]) -{ - namespace mpf = yabloc::modularized_particle_filter; - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} diff --git a/localization/yabloc/particle_filter/modularized_particle_filter/README.md b/localization/yabloc/particle_filter/modularized_particle_filter/README.md index 9722ec93542f9..a14ba0b131efb 100644 --- a/localization/yabloc/particle_filter/modularized_particle_filter/README.md +++ b/localization/yabloc/particle_filter/modularized_particle_filter/README.md @@ -36,14 +36,15 @@ colcon test-result --verbose --all ### Parameters -| Name | Type | Default | Description | -|-------------------------------|--------|---------|-----------------------------------------------------------------------------------| -| `prediction_rate` | double | 50 | frequency of forecast updates, in Hz | -| `visualize` | bool | false | whether particles are also published in visualization_msgs or not | -| `num_of_particles` | int | 500 | the number of particles | -| `resampling_interval_seconds` | double | 1.0 | the interval of particle resamping | -| `static_linear_covariance` | double | 0.01 | to override the covariance of `/twist`. When using `/twist_cov`, it has no effect | -| `static_angular_covariance` | double | 0.01 | to override the covariance of `/twist`. When using `/twist_cov`, it has no effect | +| Name | Type | Default | Description | +|-------------------------------|--------|------------|-----------------------------------------------------------------------------------| +| `prediction_rate` | double | 50 | frequency of forecast updates, in Hz | +| `visualize` | bool | false | whether particles are also published in visualization_msgs or not | +| `num_of_particles` | int | 500 | the number of particles | +| `resampling_interval_seconds` | double | 1.0 | the interval of particle resamping | +| `static_linear_covariance` | double | 0.01 | to override the covariance of `/twist`. When using `/twist_cov`, it has no effect | +| `static_angular_covariance` | double | 0.01 | to override the covariance of `/twist`. When using `/twist_cov`, it has no effect | +| `cov_xx_yy`         | list | [2.0,0.25] | the covariance of initial pose | ## Corrector diff --git a/localization/yabloc/particle_filter/modularized_particle_filter/config/predictor.param.yaml b/localization/yabloc/particle_filter/modularized_particle_filter/config/predictor.param.yaml index 681f13d0956ae..16f4273b128f5 100644 --- a/localization/yabloc/particle_filter/modularized_particle_filter/config/predictor.param.yaml +++ b/localization/yabloc/particle_filter/modularized_particle_filter/config/predictor.param.yaml @@ -9,4 +9,6 @@ num_of_particles: 500 prediction_rate: 50.0 - is_swap_mode: false # developing feature \ No newline at end of file + is_swap_mode: false # developing feature + + cov_xx_yy: [2.0,0.25] diff --git a/localization/yabloc/particle_filter/modularized_particle_filter/include/modularized_particle_filter/prediction/predictor.hpp b/localization/yabloc/particle_filter/modularized_particle_filter/include/modularized_particle_filter/prediction/predictor.hpp index 7d5d8cf48d66f..8e0de264b2583 100644 --- a/localization/yabloc/particle_filter/modularized_particle_filter/include/modularized_particle_filter/prediction/predictor.hpp +++ b/localization/yabloc/particle_filter/modularized_particle_filter/include/modularized_particle_filter/prediction/predictor.hpp @@ -19,6 +19,7 @@ #include "modularized_particle_filter/prediction/experimental/suspension_adaptor.hpp" #include "modularized_particle_filter/prediction/resampler.hpp" +#include #include #include @@ -27,6 +28,7 @@ #include #include #include +#include #include @@ -35,11 +37,13 @@ namespace yabloc::modularized_particle_filter class Predictor : public rclcpp::Node { public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW using ParticleArray = modularized_particle_filter_msgs::msg::ParticleArray; using PoseStamped = geometry_msgs::msg::PoseStamped; using PoseCovStamped = geometry_msgs::msg::PoseWithCovarianceStamped; using TwistCovStamped = geometry_msgs::msg::TwistWithCovarianceStamped; using TwistStamped = geometry_msgs::msg::TwistStamped; + using Marker = visualization_msgs::msg::Marker; Predictor(); @@ -52,6 +56,8 @@ class Predictor : public rclcpp::Node const float static_linear_covariance_; // Const value for Z angular velocity covariance const float static_angular_covariance_; + // Const value for initial pose covariance + const std::vector cov_xx_yy_; // Subscriber rclcpp::Subscription::SharedPtr initialpose_sub_; @@ -63,6 +69,7 @@ class Predictor : public rclcpp::Node rclcpp::Publisher::SharedPtr predicted_particles_pub_; rclcpp::Publisher::SharedPtr pose_pub_; rclcpp::Publisher::SharedPtr pose_cov_pub_; + rclcpp::Publisher::SharedPtr marker_pub_; std::unique_ptr tf2_broadcaster_; // Timer callback @@ -92,6 +99,10 @@ class Predictor : public rclcpp::Node ParticleArray & particle_array, const TwistCovStamped & twist, double dt); // void publish_mean_pose(const geometry_msgs::msg::Pose & mean_pose, const rclcpp::Time & stamp); + void publish_range_marker(const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent); + PoseCovStamped rectify_initial_pose( + const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent, + const PoseCovStamped & raw_initialpose) const; }; } // namespace yabloc::modularized_particle_filter diff --git a/localization/yabloc/particle_filter/modularized_particle_filter/src/prediction/predictor.cpp b/localization/yabloc/particle_filter/modularized_particle_filter/src/prediction/predictor.cpp index 69bf363790e5f..9486ec9936395 100644 --- a/localization/yabloc/particle_filter/modularized_particle_filter/src/prediction/predictor.cpp +++ b/localization/yabloc/particle_filter/modularized_particle_filter/src/prediction/predictor.cpp @@ -36,7 +36,8 @@ Predictor::Predictor() number_of_particles_(declare_parameter("num_of_particles")), resampling_interval_seconds_(declare_parameter("resampling_interval_seconds")), static_linear_covariance_(declare_parameter("static_linear_covariance")), - static_angular_covariance_(declare_parameter("static_angular_covariance")) + static_angular_covariance_(declare_parameter("static_angular_covariance")), + cov_xx_yy_{this->template declare_parameter>("cov_xx_yy")} { tf2_broadcaster_ = std::make_unique(*this); @@ -44,6 +45,7 @@ Predictor::Predictor() predicted_particles_pub_ = create_publisher("predicted_particles", 10); pose_pub_ = create_publisher("pose", 10); pose_cov_pub_ = create_publisher("pose_with_covariance", 10); + marker_pub_ = create_publisher("debug/init_marker", 10); // Subscribers using std::placeholders::_1; @@ -74,7 +76,23 @@ Predictor::Predictor() void Predictor::on_initial_pose(const PoseCovStamped::ConstSharedPtr initialpose) { - initialize_particles(*initialpose); + // Publish initial pose marker + auto position = initialpose->pose.pose.position; + Eigen::Vector3f pos_vec3f; + pos_vec3f << position.x, position.y, position.z; + + auto orientation = initialpose->pose.pose.orientation; + float theta = 2 * std::atan2(orientation.z, orientation.w); + Eigen::Vector3f tangent; + tangent << std::cos(theta), std::sin(theta), 0; + + publish_range_marker(pos_vec3f, tangent); + + // Rectify initial pose + auto initialpose_rectified = rectify_initial_pose(pos_vec3f, tangent, *initialpose); + + // Initialize particles given the initial pose and its covariance + initialize_particles(initialpose_rectified); } void Predictor::initialize_particles(const PoseCovStamped & initialpose) @@ -297,4 +315,69 @@ void Predictor::publish_mean_pose( } } +void Predictor::publish_range_marker(const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent) +{ + Marker msg; + msg.type = Marker::LINE_STRIP; + msg.header.stamp = get_clock()->now(); + msg.header.frame_id = "map"; + msg.scale.x = 0.2; + msg.scale.y = 0.2; + + msg.color.r = 0; + msg.color.g = 1; + msg.color.b = 0; + msg.color.a = 1; + + auto cast2gp = [](const Eigen::Vector3f & vec3f) -> geometry_msgs::msg::Point { + geometry_msgs::msg::Point p; + p.x = vec3f.x(); + p.y = vec3f.y(); + p.z = vec3f.z(); + return p; + }; + + Eigen::Vector3f binormal; + binormal << -tangent.y(), tangent.x(), tangent.z(); + + msg.points.push_back(cast2gp(pos + tangent + binormal)); + msg.points.push_back(cast2gp(pos + tangent - binormal)); + msg.points.push_back(cast2gp(pos - tangent - binormal)); + msg.points.push_back(cast2gp(pos - tangent + binormal)); + msg.points.push_back(cast2gp(pos + tangent + binormal)); + + marker_pub_->publish(msg); +} + +Predictor::PoseCovStamped Predictor::rectify_initial_pose( + const Eigen::Vector3f & pos, const Eigen::Vector3f & tangent, + const PoseCovStamped & raw_initialpose) const +{ + PoseCovStamped msg = raw_initialpose; + msg.header.frame_id = "map"; + msg.pose.pose.position.x = pos.x(); + msg.pose.pose.position.y = pos.y(); + msg.pose.pose.position.z = pos.z(); + + float theta = std::atan2(tangent.y(), tangent.x()); + + msg.pose.pose.orientation.w = std::cos(theta / 2); + msg.pose.pose.orientation.x = 0; + msg.pose.pose.orientation.y = 0; + msg.pose.pose.orientation.z = std::sin(theta / 2); + + Eigen::Matrix2f cov; + cov << cov_xx_yy_.at(0), 0, 0, cov_xx_yy_.at(1); + Eigen::Rotation2D r(theta); + cov = r * cov * r.inverse(); + + msg.pose.covariance.at(6 * 0 + 0) = cov(0, 0); + msg.pose.covariance.at(6 * 0 + 1) = cov(0, 1); + msg.pose.covariance.at(6 * 1 + 0) = cov(1, 0); + msg.pose.covariance.at(6 * 1 + 1) = cov(1, 1); + msg.pose.covariance.at(6 * 5 + 5) = 0.0076; // 0.0076 = (5deg)^2 + + return msg; +} + } // namespace yabloc::modularized_particle_filter \ No newline at end of file diff --git a/localization/yabloc/yabloc_launch/launch/impl/initializer.launch.xml b/localization/yabloc/yabloc_launch/launch/impl/initializer.launch.xml index c297a6bd92639..36ff090c2b10c 100644 --- a/localization/yabloc/yabloc_launch/launch/impl/initializer.launch.xml +++ b/localization/yabloc/yabloc_launch/launch/impl/initializer.launch.xml @@ -25,11 +25,4 @@ - - - - - - - diff --git a/localization/yabloc/yabloc_launch/launch/impl/pf.launch.xml b/localization/yabloc/yabloc_launch/launch/impl/pf.launch.xml index 6ad4e6c50e40a..c203e3047bdc5 100644 --- a/localization/yabloc/yabloc_launch/launch/impl/pf.launch.xml +++ b/localization/yabloc/yabloc_launch/launch/impl/pf.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/localization/yabloc/yabloc_launch/launch/yabloc.launch.xml b/localization/yabloc/yabloc_launch/launch/yabloc.launch.xml index 9cdca89365989..2179a6341b566 100644 --- a/localization/yabloc/yabloc_launch/launch/yabloc.launch.xml +++ b/localization/yabloc/yabloc_launch/launch/yabloc.launch.xml @@ -18,7 +18,6 @@ - diff --git a/localization/yabloc/yabloc_launch/launch/yabloc_multi_camera.launch.xml b/localization/yabloc/yabloc_launch/launch/yabloc_multi_camera.launch.xml index d5deaf445ca43..ab667e7f8e635 100644 --- a/localization/yabloc/yabloc_launch/launch/yabloc_multi_camera.launch.xml +++ b/localization/yabloc/yabloc_launch/launch/yabloc_multi_camera.launch.xml @@ -26,7 +26,6 @@ - diff --git a/localization/yabloc/yabloc_launch/package.xml b/localization/yabloc/yabloc_launch/package.xml index d5e67a4fef185..657bbaa8587fc 100644 --- a/localization/yabloc/yabloc_launch/package.xml +++ b/localization/yabloc/yabloc_launch/package.xml @@ -32,7 +32,6 @@ gnss_pose_initializer camera_pose_initializer - particle_initializer semantic_segmentation camera_particle_corrector