Skip to content

Commit

Permalink
feat(planning_debug_tools)!: replace tier4_debug_msgs with tier4_inte…
Browse files Browse the repository at this point in the history
…rnal_debug_msgs (#200)

Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
mitsudome-r authored Jan 23, 2025
1 parent d401618 commit aa738de
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@
#include "planning_debug_tools/util.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_internal_debug_msgs/msg/float64_multi_array_stamped.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tier4_debug_msgs/msg/float64_multi_array_stamped.hpp"
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"

#include <iostream>
Expand Down
2 changes: 1 addition & 1 deletion planning/planning_debug_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
Expand All @@ -25,7 +26,6 @@
<depend>nav_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_planning_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@

from autoware_adapi_v1_msgs.msg import OperationModeState
from autoware_control_msgs.msg import Control as AckermannControlCommand
from autoware_internal_debug_msgs.msg import Float32MultiArrayStamped
from autoware_internal_debug_msgs.msg import Float32Stamped
from autoware_planning_msgs.msg import Path
from autoware_planning_msgs.msg import Trajectory
from autoware_vehicle_msgs.msg import VelocityReport
Expand All @@ -29,8 +31,6 @@
from tf2_ros import LookupException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener
from tier4_debug_msgs.msg import Float32MultiArrayStamped
from tier4_debug_msgs.msg import Float32Stamped
from tier4_planning_msgs.msg import PathWithLaneId
from tier4_planning_msgs.msg import VelocityLimit

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,9 @@
import os
import sys

from autoware_internal_debug_msgs.msg import Float64Stamped
import rclpy
from rclpy.node import Node
from tier4_debug_msgs.msg import Float64Stamped


class ProcessingTimeSubscriber(Node):
Expand Down

0 comments on commit aa738de

Please sign in to comment.