Skip to content

Commit 6fe8922

Browse files
authored
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (#9857)
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/control_performance_analysis Signed-off-by: vish0012 <vishalchhn42@gmail.com>
1 parent 56ff9b8 commit 6fe8922

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

Diff for: control/control_performance_analysis/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<build_depend>builtin_interfaces</build_depend>
2626

2727
<depend>autoware_control_msgs</depend>
28+
<depend>autoware_internal_debug_msgs</depend>
2829
<depend>autoware_motion_utils</depend>
2930
<depend>autoware_planning_msgs</depend>
3031
<depend>autoware_signal_processing</depend>
@@ -41,7 +42,6 @@
4142
<depend>tf2</depend>
4243
<depend>tf2_eigen</depend>
4344
<depend>tf2_ros</depend>
44-
<depend>tier4_debug_msgs</depend>
4545
<exec_depend>autoware_global_parameter_loader</exec_depend>
4646
<exec_depend>builtin_interfaces</exec_depend>
4747
<exec_depend>rosidl_default_runtime</exec_depend>

Diff for: control/control_performance_analysis/scripts/control_performance_plot.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,13 +17,13 @@
1717
import argparse
1818
import math
1919

20+
from autoware_internal_debug_msgs.msg import BoolStamped
2021
from control_performance_analysis.msg import DrivingMonitorStamped
2122
from control_performance_analysis.msg import ErrorStamped
2223
import matplotlib.pyplot as plt
2324
from nav_msgs.msg import Odometry
2425
import rclpy
2526
from rclpy.node import Node
26-
from tier4_debug_msgs.msg import BoolStamped
2727

2828
parser = argparse.ArgumentParser()
2929
parser.add_argument("-i", "--interval", help="interval distance to plot")

0 commit comments

Comments
 (0)