Skip to content

Commit bdde8e3

Browse files
committed
fix autoware_utils header
Signed-off-by: kazu-321 <kzs321kzs@gmail.com>
1 parent 0e67050 commit bdde8e3

File tree

3 files changed

+8
-7
lines changed

3 files changed

+8
-7
lines changed

localization/autoware_pose_initializer/package.xml

+2-1
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,8 @@
2323
<depend>autoware_component_interface_utils</depend>
2424
<depend>autoware_map_height_fitter</depend>
2525
<depend>autoware_motion_utils</depend>
26-
<depend>autoware_utils</depend>
26+
<depend>autoware_utils_logging</depend>
27+
<depend>autoware_utils_diagnostics</depend>
2728
<depend>geometry_msgs</depend>
2829
<depend>rclcpp</depend>
2930
<depend>rclcpp_components</depend>

localization/autoware_pose_initializer/src/pose_initializer_core.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options)
4141
gnss_particle_covariance_ = get_covariance_parameter(this, "gnss_particle_covariance");
4242

4343
diagnostics_pose_reliable_ =
44-
std::make_unique<autoware_utils::DiagnosticsInterface>(this, "pose_initializer_status");
44+
std::make_unique<autoware_utils_diagnostics::DiagnosticsInterface>(this, "pose_initializer_status");
4545

4646
if (declare_parameter<bool>("ekf_enabled")) {
4747
ekf_localization_trigger_ = std::make_unique<EkfLocalizationTriggerModule>(this);
@@ -64,7 +64,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options)
6464
if (declare_parameter<bool>("pose_error_check_enabled")) {
6565
pose_error_check_ = std::make_unique<PoseErrorCheckModule>(this);
6666
}
67-
logger_configure_ = std::make_unique<autoware_utils::LoggerLevelConfigure>(this);
67+
logger_configure_ = std::make_unique<autoware_utils_logging::LoggerLevelConfigure>(this);
6868

6969
change_state(State::Message::UNINITIALIZED);
7070

localization/autoware_pose_initializer/src/pose_initializer_core.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717

1818
#include <autoware/component_interface_specs_universe/localization.hpp>
1919
#include <autoware/component_interface_utils/rclcpp.hpp>
20-
#include <autoware_utils/ros/diagnostics_interface.hpp>
21-
#include <autoware_utils/ros/logger_level_configure.hpp>
20+
#include <autoware_utils_diagnostics/diagnostics_interface.hpp>
21+
#include <autoware_utils_logging/logger_level_configure.hpp>
2222
#include <rclcpp/rclcpp.hpp>
2323

2424
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
@@ -59,8 +59,8 @@ class PoseInitializer : public rclcpp::Node
5959
std::unique_ptr<PoseErrorCheckModule> pose_error_check_;
6060
std::unique_ptr<EkfLocalizationTriggerModule> ekf_localization_trigger_;
6161
std::unique_ptr<NdtLocalizationTriggerModule> ndt_localization_trigger_;
62-
std::unique_ptr<autoware_utils::LoggerLevelConfigure> logger_configure_;
63-
std::unique_ptr<autoware_utils::DiagnosticsInterface> diagnostics_pose_reliable_;
62+
std::unique_ptr<autoware_utils_logging::LoggerLevelConfigure> logger_configure_;
63+
std::unique_ptr<autoware_utils_diagnostics::DiagnosticsInterface> diagnostics_pose_reliable_;
6464
double stop_check_duration_;
6565

6666
void change_node_trigger(bool flag, bool need_spin = false);

0 commit comments

Comments
 (0)