Skip to content

Commit

Permalink
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fie…
Browse files Browse the repository at this point in the history
…s localization/autoware_ekf_localizer (#9860)

Signed-off-by: vish0012 <vishalchhn42@gmail.com>
Co-authored-by: SakodaShintaro <shintaro.sakoda@tier4.jp>
  • Loading branch information
vish0012 and SakodaShintaro authored Jan 9, 2025
1 parent 7ac40b7 commit 22ca703
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 23 deletions.
22 changes: 11 additions & 11 deletions localization/autoware_ekf_localizer/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,17 +44,17 @@ This package includes the following features:

### Published Topics

| Name | Type | Description |
| --------------------------------- | ------------------------------------------------ | ----------------------------------------------------- |
| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. |
| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. |
| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. |
| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias |
| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias |
| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. |
| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. |
| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. |
| `debug/processing_time_ms` | `tier4_debug_msgs::msg::Float64Stamped` | The processing time [ms]. |
| Name | Type | Description |
| --------------------------------- | --------------------------------------------------- | ----------------------------------------------------- |
| `ekf_odom` | `nav_msgs::msg::Odometry` | Estimated odometry. |
| `ekf_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose. |
| `ekf_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance. |
| `ekf_biased_pose` | `geometry_msgs::msg::PoseStamped` | Estimated pose including the yaw bias |
| `ekf_biased_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Estimated pose with covariance including the yaw bias |
| `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. |
| `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. |
| `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. |
| `debug/processing_time_ms` | `autoware_internal_debug_msgs::msg::Float64Stamped` | The processing time [ms]. |

### Published TF

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_multi_array_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
Expand All @@ -34,8 +36,6 @@
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <std_srvs/srv/set_bool.hpp>
#include <tier4_debug_msgs/msg/float64_multi_array_stamped.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>

#include <tf2/LinearMath/Quaternion.h>
#include <tf2/utils.h>
Expand Down Expand Up @@ -78,15 +78,16 @@ class EKFLocalizer : public rclcpp::Node
//!< @brief ekf estimated twist with covariance publisher
rclcpp::Publisher<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr pub_twist_cov_;
//!< @brief ekf estimated yaw bias publisher
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_yaw_bias_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr pub_yaw_bias_;
//!< @brief ekf estimated yaw bias publisher
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_biased_pose_;
//!< @brief ekf estimated yaw bias publisher
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pub_biased_pose_cov_;
//!< @brief diagnostics publisher
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr pub_diag_;
//!< @brief processing_time publisher
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
pub_processing_time_;
//!< @brief initial pose subscriber
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr sub_initialpose_;
//!< @brief measurement pose with covariance subscriber
Expand Down
2 changes: 1 addition & 1 deletion localization/autoware_ekf_localizer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

<build_depend>eigen</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_kalman_filter</depend>
<depend>autoware_localization_util</depend>
<depend>autoware_universe_utils</depend>
Expand All @@ -34,7 +35,6 @@
<depend>std_srvs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
16 changes: 9 additions & 7 deletions localization/autoware_ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,13 +70,14 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options)
pub_twist_ = create_publisher<geometry_msgs::msg::TwistStamped>("ekf_twist", 1);
pub_twist_cov_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
"ekf_twist_with_covariance", 1);
pub_yaw_bias_ = create_publisher<tier4_debug_msgs::msg::Float64Stamped>("estimated_yaw_bias", 1);
pub_yaw_bias_ =
create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>("estimated_yaw_bias", 1);
pub_biased_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>("ekf_biased_pose", 1);
pub_biased_pose_cov_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
"ekf_biased_pose_with_covariance", 1);
pub_diag_ = this->create_publisher<diagnostic_msgs::msg::DiagnosticArray>("/diagnostics", 10);
pub_processing_time_ =
create_publisher<tier4_debug_msgs::msg::Float64Stamped>("debug/processing_time_ms", 1);
pub_processing_time_ = create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", 1);
sub_initialpose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1));
sub_pose_with_cov_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
Expand Down Expand Up @@ -235,9 +236,10 @@ void EKFLocalizer::timer_callback()

/* publish processing time */
const double elapsed_time = stop_watch_timer_cb_.toc();
pub_processing_time_->publish(tier4_debug_msgs::build<tier4_debug_msgs::msg::Float64Stamped>()
.stamp(current_time)
.data(elapsed_time));
pub_processing_time_->publish(
autoware_internal_debug_msgs::build<autoware_internal_debug_msgs::msg::Float64Stamped>()
.stamp(current_time)
.data(elapsed_time));
}

/*
Expand Down Expand Up @@ -343,7 +345,7 @@ void EKFLocalizer::publish_estimate_result(
pub_twist_cov_->publish(twist_cov);

/* publish yaw bias */
tier4_debug_msgs::msg::Float64Stamped yawb;
autoware_internal_debug_msgs::msg::Float64Stamped yawb;
yawb.stamp = current_ekf_twist.header.stamp;
yawb.data = ekf_module_->get_yaw_bias();
pub_yaw_bias_->publish(yawb);
Expand Down

0 comments on commit 22ca703

Please sign in to comment.