diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml
index 02c6da20e17da..1ba5bc9ecdb26 100644
--- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml
+++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml
@@ -13,7 +13,7 @@
-
+
@@ -30,7 +30,7 @@
-
+
@@ -59,7 +59,7 @@
-
+
-
+
-
+
-
+
diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml
index c4de9c04dcaf2..d91ef7a6de52b 100644
--- a/launch/tier4_localization_launch/package.xml
+++ b/launch/tier4_localization_launch/package.xml
@@ -14,11 +14,8 @@
ament_cmake_auto
autoware_cmake
- ar_tag_based_localizer
+
automatic_pose_initializer
- eagleye_geo_pose_fusion
- eagleye_gnss_converter
- eagleye_rt
ekf_localizer
geo_pose_projector
gyro_odometer
@@ -27,11 +24,14 @@
pose_initializer
pose_instability_detector
topic_tools
- yabloc_common
- yabloc_image_processing
- yabloc_monitor
- yabloc_particle_filter
- yabloc_pose_initializer
+
+
+
+
+
+
+
+
ament_lint_auto
autoware_lint_common
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml
index ab9ed65999048..094a611ea7778 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml
@@ -35,9 +35,9 @@
-
-
-
+
+
+
-
+ -->
+
+
-
+ -->
+
+
-
+ -->
+
+
-
-
-
+
+
+
-
+ -->
+
+
-
+ -->
+
+
-
-
-
+
+
+
-
+ -->
+
+
-
+ -->
+
+
-
+ -->
+
+
-
+ -->
+
+
@@ -231,13 +231,13 @@
-
-
-
+
+
+
diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml
index 528038c5158b2..47c66c8f8a947 100644
--- a/launch/tier4_perception_launch/launch/perception.launch.xml
+++ b/launch/tier4_perception_launch/launch/perception.launch.xml
@@ -231,7 +231,7 @@
-
+
diff --git a/perception/map_based_prediction/CMakeLists.txt b/perception/map_based_prediction/CMakeLists.txt
index 9378e09f099cc..53c78b54bc2ab 100644
--- a/perception/map_based_prediction/CMakeLists.txt
+++ b/perception/map_based_prediction/CMakeLists.txt
@@ -6,8 +6,6 @@ autoware_package()
find_package(Eigen3 REQUIRED)
-find_package(glog REQUIRED)
-
include_directories(
SYSTEM
${EIGEN3_INCLUDE_DIR}
@@ -19,8 +17,6 @@ ament_auto_add_library(map_based_prediction_node SHARED
src/debug.cpp
)
-target_link_libraries(map_based_prediction_node glog::glog)
-
rclcpp_components_register_node(map_based_prediction_node
PLUGIN "map_based_prediction::MapBasedPredictionNode"
EXECUTABLE map_based_prediction
diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml
index b07d9855f9821..6a1354b37928f 100644
--- a/perception/map_based_prediction/package.xml
+++ b/perception/map_based_prediction/package.xml
@@ -18,7 +18,6 @@
autoware_auto_perception_msgs
interpolation
lanelet2_extension
- libgoogle-glog-dev
motion_utils
rclcpp
rclcpp_components
diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp
index 75c1d61e0a19c..1b00325cda8ea 100644
--- a/perception/map_based_prediction/src/map_based_prediction_node.cpp
+++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp
@@ -43,8 +43,6 @@
#include
#endif
-#include
-
#include
#include
#include
@@ -728,8 +726,6 @@ void replaceObjectYawWithLaneletsYaw(
MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options)
: Node("map_based_prediction", node_options), debug_accumulated_time_(0.0)
{
- google::InitGoogleLogging("map_based_prediction_node");
- google::InstallFailureSignalHandler();
enable_delay_compensation_ = declare_parameter("enable_delay_compensation");
prediction_time_horizon_ = declare_parameter("prediction_time_horizon");
lateral_control_time_horizon_ =