@@ -70,13 +70,14 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options)
70
70
pub_twist_ = create_publisher<geometry_msgs::msg::TwistStamped>(" ekf_twist" , 1 );
71
71
pub_twist_cov_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
72
72
" ekf_twist_with_covariance" , 1 );
73
- pub_yaw_bias_ = create_publisher<tier4_debug_msgs::msg::Float64Stamped>(" estimated_yaw_bias" , 1 );
73
+ pub_yaw_bias_ =
74
+ create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(" estimated_yaw_bias" , 1 );
74
75
pub_biased_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>(" ekf_biased_pose" , 1 );
75
76
pub_biased_pose_cov_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
76
77
" ekf_biased_pose_with_covariance" , 1 );
77
78
pub_diag_ = this ->create_publisher <diagnostic_msgs::msg::DiagnosticArray>(" /diagnostics" , 10 );
78
- pub_processing_time_ =
79
- create_publisher<tier4_debug_msgs::msg::Float64Stamped>( " debug/processing_time_ms" , 1 );
79
+ pub_processing_time_ = create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
80
+ " debug/processing_time_ms" , 1 );
80
81
sub_initialpose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
81
82
" initialpose" , 1 , std::bind (&EKFLocalizer::callback_initial_pose, this , _1));
82
83
sub_pose_with_cov_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
@@ -235,9 +236,10 @@ void EKFLocalizer::timer_callback()
235
236
236
237
/* publish processing time */
237
238
const double elapsed_time = stop_watch_timer_cb_.toc ();
238
- pub_processing_time_->publish (tier4_debug_msgs::build<tier4_debug_msgs::msg::Float64Stamped>()
239
- .stamp (current_time)
240
- .data (elapsed_time));
239
+ pub_processing_time_->publish (
240
+ autoware_internal_debug_msgs::build<autoware_internal_debug_msgs::msg::Float64Stamped>()
241
+ .stamp (current_time)
242
+ .data (elapsed_time));
241
243
}
242
244
243
245
/*
@@ -343,7 +345,7 @@ void EKFLocalizer::publish_estimate_result(
343
345
pub_twist_cov_->publish (twist_cov);
344
346
345
347
/* publish yaw bias */
346
- tier4_debug_msgs ::msg::Float64Stamped yawb;
348
+ autoware_internal_debug_msgs ::msg::Float64Stamped yawb;
347
349
yawb.stamp = current_ekf_twist.header .stamp ;
348
350
yawb.data = ekf_module_->get_yaw_bias ();
349
351
pub_yaw_bias_->publish (yawb);
0 commit comments