File tree 3 files changed +8
-7
lines changed
localization/autoware_pose_initializer
3 files changed +8
-7
lines changed Original file line number Diff line number Diff line change 23
23
<depend >autoware_component_interface_utils</depend >
24
24
<depend >autoware_map_height_fitter</depend >
25
25
<depend >autoware_motion_utils</depend >
26
- <depend >autoware_utils</depend >
26
+ <depend >autoware_utils_logging</depend >
27
+ <depend >autoware_utils_diagnostics</depend >
27
28
<depend >geometry_msgs</depend >
28
29
<depend >rclcpp</depend >
29
30
<depend >rclcpp_components</depend >
Original file line number Diff line number Diff line change @@ -41,7 +41,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options)
41
41
gnss_particle_covariance_ = get_covariance_parameter (this , " gnss_particle_covariance" );
42
42
43
43
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" );
45
45
46
46
if (declare_parameter<bool >(" ekf_enabled" )) {
47
47
ekf_localization_trigger_ = std::make_unique<EkfLocalizationTriggerModule>(this );
@@ -64,7 +64,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options)
64
64
if (declare_parameter<bool >(" pose_error_check_enabled" )) {
65
65
pose_error_check_ = std::make_unique<PoseErrorCheckModule>(this );
66
66
}
67
- logger_configure_ = std::make_unique<autoware_utils ::LoggerLevelConfigure>(this );
67
+ logger_configure_ = std::make_unique<autoware_utils_logging ::LoggerLevelConfigure>(this );
68
68
69
69
change_state (State::Message::UNINITIALIZED);
70
70
Original file line number Diff line number Diff line change 17
17
18
18
#include < autoware/component_interface_specs_universe/localization.hpp>
19
19
#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>
22
22
#include < rclcpp/rclcpp.hpp>
23
23
24
24
#include < geometry_msgs/msg/pose_with_covariance_stamped.hpp>
@@ -59,8 +59,8 @@ class PoseInitializer : public rclcpp::Node
59
59
std::unique_ptr<PoseErrorCheckModule> pose_error_check_;
60
60
std::unique_ptr<EkfLocalizationTriggerModule> ekf_localization_trigger_;
61
61
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_;
64
64
double stop_check_duration_;
65
65
66
66
void change_node_trigger (bool flag, bool need_spin = false );
You can’t perform that action at this time.
0 commit comments