Skip to content

Commit f36d072

Browse files
authored
feat(autoware_goal_distance_calculator)!: tier4_debug_msgs to autoware_internal_debug_msgs for autoware_goal_distance_calculator (#9833)
Signed-off-by: vish0012 <vishalchhn42@gmail.com>
1 parent 0ac8580 commit f36d072

File tree

4 files changed

+14
-13
lines changed

4 files changed

+14
-13
lines changed

common/autoware_goal_distance_calculator/Readme.md

+6-6
Original file line numberDiff line numberDiff line change
@@ -17,12 +17,12 @@ This node publishes deviation of self-pose from goal pose.
1717

1818
### Output
1919

20-
| Name | Type | Description |
21-
| ------------------------ | --------------------------------------- | ------------------------------------------------------------- |
22-
| `deviation/lateral` | `tier4_debug_msgs::msg::Float64Stamped` | publish lateral deviation of self-pose from goal pose[m] |
23-
| `deviation/longitudinal` | `tier4_debug_msgs::msg::Float64Stamped` | publish longitudinal deviation of self-pose from goal pose[m] |
24-
| `deviation/yaw` | `tier4_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[rad] |
25-
| `deviation/yaw_deg` | `tier4_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[deg] |
20+
| Name | Type | Description |
21+
| ------------------------ | --------------------------------------------------- | ------------------------------------------------------------- |
22+
| `deviation/lateral` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish lateral deviation of self-pose from goal pose[m] |
23+
| `deviation/longitudinal` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish longitudinal deviation of self-pose from goal pose[m] |
24+
| `deviation/yaw` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[rad] |
25+
| `deviation/yaw_deg` | `autoware_internal_debug_msgs::msg::Float64Stamped` | publish yaw deviation of self-pose from goal pose[deg] |
2626

2727
## Parameters
2828

common/autoware_goal_distance_calculator/include/autoware/goal_distance_calculator/goal_distance_calculator_node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,9 @@
2222
#include <autoware/universe_utils/ros/self_pose_listener.hpp>
2323
#include <rclcpp/rclcpp.hpp>
2424

25+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2526
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
2627
#include <geometry_msgs/msg/pose_stamped.hpp>
27-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
2828

2929
#include <tf2_ros/transform_listener.h>
3030

common/autoware_goal_distance_calculator/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,12 +10,12 @@
1010
<buildtool_depend>ament_cmake</buildtool_depend>
1111
<buildtool_depend>autoware_cmake</buildtool_depend>
1212

13+
<depend>autoware_internal_debug_msgs</depend>
1314
<depend>autoware_planning_msgs</depend>
1415
<depend>autoware_universe_utils</depend>
1516
<depend>geometry_msgs</depend>
1617
<depend>rclcpp</depend>
1718
<depend>rclcpp_components</depend>
18-
<depend>tier4_debug_msgs</depend>
1919

2020
<test_depend>ament_lint_auto</test_depend>
2121
<test_depend>autoware_lint_common</test_depend>

common/autoware_goal_distance_calculator/src/goal_distance_calculator_node.cpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <rclcpp/rclcpp.hpp>
1919
#include <rclcpp/timer.hpp>
2020

21-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
21+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2222

2323
#include <chrono>
2424
#include <functional>
@@ -100,12 +100,13 @@ void GoalDistanceCalculatorNode::onTimer()
100100
using autoware::universe_utils::rad2deg;
101101
const auto & deviation = output.goal_deviation;
102102

103-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>(
103+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
104104
"deviation/lateral", deviation.lateral);
105-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>(
105+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
106106
"deviation/longitudinal", deviation.longitudinal);
107-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>("deviation/yaw", deviation.yaw);
108-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>(
107+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
108+
"deviation/yaw", deviation.yaw);
109+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
109110
"deviation/yaw_deg", rad2deg(deviation.yaw));
110111
RCLCPP_INFO_THROTTLE(
111112
this->get_logger(), *this->get_clock(), 1000,

0 commit comments

Comments
 (0)