Skip to content

Commit 22ca703

Browse files
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fies localization/autoware_ekf_localizer (#9860)
Signed-off-by: vish0012 <vishalchhn42@gmail.com> Co-authored-by: SakodaShintaro <shintaro.sakoda@tier4.jp>
1 parent 7ac40b7 commit 22ca703

File tree

4 files changed

+26
-23
lines changed

4 files changed

+26
-23
lines changed

localization/autoware_ekf_localizer/README.md

+11-11
Original file line numberDiff line numberDiff line change
@@ -44,17 +44,17 @@ This package includes the following features:
4444

4545
### Published Topics
4646

47-
| Name | Type | Description |
48-
| --------------------------------- | ------------------------------------------------ | ----------------------------------------------------- |
49-
| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. |
50-
| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. |
51-
| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. |
52-
| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias |
53-
| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias |
54-
| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. |
55-
| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. |
56-
| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. |
57-
| `debug/processing_time_ms` | `tier4_debug_msgs::msg::Float64Stamped` | The processing time [ms]. |
47+
| Name | Type | Description |
48+
| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- |
49+
| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. |
50+
| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. |
51+
| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. |
52+
| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias |
53+
| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias |
54+
| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. |
55+
| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. |
56+
| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. |
57+
| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. |
5858

5959
### Published TF
6060

localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@
2525
#include <autoware/universe_utils/system/stop_watch.hpp>
2626
#include <rclcpp/rclcpp.hpp>
2727

28+
#include <autoware_internal_debug_msgs/msg/float64_multi_array_stamped.hpp>
29+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2830
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
2931
#include <geometry_msgs/msg/pose_array.hpp>
3032
#include <geometry_msgs/msg/pose_stamped.hpp>
@@ -34,8 +36,6 @@
3436
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
3537
#include <nav_msgs/msg/odometry.hpp>
3638
#include <std_srvs/srv/set_bool.hpp>
37-
#include <tier4_debug_msgs/msg/float64_multi_array_stamped.hpp>
38-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
3939

4040
#include <tf2/LinearMath/Quaternion.h>
4141
#include <tf2/utils.h>
@@ -78,15 +78,16 @@ class EKFLocalizer : public rclcpp::Node
7878
//!< @brief ekf estimated twist with covariance publisher
7979
rclcpp::Publisher<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr pub_twist_cov_;
8080
//!< @brief ekf estimated yaw bias publisher
81-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_yaw_bias_;
81+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr pub_yaw_bias_;
8282
//!< @brief ekf estimated yaw bias publisher
8383
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_biased_pose_;
8484
//!< @brief ekf estimated yaw bias publisher
8585
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pub_biased_pose_cov_;
8686
//!< @brief diagnostics publisher
8787
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr pub_diag_;
8888
//!< @brief processing_time publisher
89-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_;
89+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
90+
pub_processing_time_;
9091
//!< @brief initial pose subscriber
9192
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr sub_initialpose_;
9293
//!< @brief measurement pose with covariance subscriber

localization/autoware_ekf_localizer/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222

2323
<build_depend>eigen</build_depend>
2424

25+
<depend>autoware_internal_debug_msgs</depend>
2526
<depend>autoware_kalman_filter</depend>
2627
<depend>autoware_localization_util</depend>
2728
<depend>autoware_universe_utils</depend>
@@ -34,7 +35,6 @@
3435
<depend>std_srvs</depend>
3536
<depend>tf2</depend>
3637
<depend>tf2_ros</depend>
37-
<depend>tier4_debug_msgs</depend>
3838

3939
<test_depend>ament_cmake_ros</test_depend>
4040
<test_depend>ament_lint_auto</test_depend>

localization/autoware_ekf_localizer/src/ekf_localizer.cpp

+9-7
Original file line numberDiff line numberDiff line change
@@ -70,13 +70,14 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options)
7070
pub_twist_ = create_publisher<geometry_msgs::msg::TwistStamped>("ekf_twist", 1);
7171
pub_twist_cov_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
7272
"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);
7475
pub_biased_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>("ekf_biased_pose", 1);
7576
pub_biased_pose_cov_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
7677
"ekf_biased_pose_with_covariance", 1);
7778
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);
8081
sub_initialpose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
8182
"initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1));
8283
sub_pose_with_cov_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
@@ -235,9 +236,10 @@ void EKFLocalizer::timer_callback()
235236

236237
/* publish processing time */
237238
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));
241243
}
242244

243245
/*
@@ -343,7 +345,7 @@ void EKFLocalizer::publish_estimate_result(
343345
pub_twist_cov_->publish(twist_cov);
344346

345347
/* publish yaw bias */
346-
tier4_debug_msgs::msg::Float64Stamped yawb;
348+
autoware_internal_debug_msgs::msg::Float64Stamped yawb;
347349
yawb.stamp = current_ekf_twist.header.stamp;
348350
yawb.data = ekf_module_->get_yaw_bias();
349351
pub_yaw_bias_->publish(yawb);

0 commit comments

Comments
 (0)