Skip to content

Commit 0b73c13

Browse files
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (#9846)
* feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files ontrol/autoware_mpc_lateral_controller Signed-off-by: vish0012 <vishalchhn42@gmail.com> * style(pre-commit): autofix --------- Signed-off-by: vish0012 <vishalchhn42@gmail.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 926ad7f commit 0b73c13

File tree

7 files changed

+20
-17
lines changed

7 files changed

+20
-17
lines changed

control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker_node.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -24,14 +24,14 @@
2424
#include <rclcpp/rclcpp.hpp>
2525

2626
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
27+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
2728
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
2829
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
2930
#include <autoware_planning_msgs/msg/trajectory.hpp>
3031
#include <autoware_vehicle_msgs/msg/control_mode_report.hpp>
3132
#include <geometry_msgs/msg/pose_stamped.hpp>
3233
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
3334
#include <nav_msgs/msg/odometry.hpp>
34-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
3535
#include <visualization_msgs/msg/marker_array.hpp>
3636

3737
#include <lanelet2_core/LaneletMap.h>
@@ -115,7 +115,8 @@ class LaneDepartureCheckerNode : public rclcpp::Node
115115
autoware::universe_utils::DebugPublisher debug_publisher_{this, "~/debug"};
116116
autoware::universe_utils::ProcessingTimePublisher processing_diag_publisher_{
117117
this, "~/debug/processing_time_ms_diag"};
118-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_publisher_;
118+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
119+
processing_time_publisher_;
119120

120121
// Timer
121122
rclcpp::TimerBase::SharedPtr timer_;

control/autoware_lane_departure_checker/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
<buildtool_depend>autoware_cmake</buildtool_depend>
1515

1616
<depend>autoware_adapi_v1_msgs</depend>
17+
<depend>autoware_internal_debug_msgs</depend>
1718
<depend>autoware_lanelet2_extension</depend>
1819
<depend>autoware_map_msgs</depend>
1920
<depend>autoware_motion_utils</depend>
@@ -32,7 +33,6 @@
3233
<depend>tf2_eigen</depend>
3334
<depend>tf2_geometry_msgs</depend>
3435
<depend>tf2_ros</depend>
35-
<depend>tier4_debug_msgs</depend>
3636

3737
<test_depend>ament_cmake_ros</test_depend>
3838
<test_depend>ament_lint_auto</test_depend>

control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp

+7-5
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o
171171

172172
// Publisher
173173
processing_time_publisher_ =
174-
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
174+
this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
175+
"~/debug/processing_time_ms", 1);
175176
// Nothing
176177

177178
// Diagnostic Updater
@@ -342,10 +343,11 @@ void LaneDepartureCheckerNode::onTimer()
342343

343344
{
344345
const auto & deviation = output_.trajectory_deviation;
345-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>(
346+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
346347
"deviation/lateral", deviation.lateral);
347-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>("deviation/yaw", deviation.yaw);
348-
debug_publisher_.publish<tier4_debug_msgs::msg::Float64Stamped>(
348+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
349+
"deviation/yaw", deviation.yaw);
350+
debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
349351
"deviation/yaw_deg", rad2deg(deviation.yaw));
350352
}
351353
processing_time_map["Node: publishTrajectoryDeviation"] = stop_watch.toc(true);
@@ -361,7 +363,7 @@ void LaneDepartureCheckerNode::onTimer()
361363

362364
processing_time_map["Total"] = stop_watch.toc("Total");
363365
processing_diag_publisher_.publish(processing_time_map);
364-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
366+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
365367
processing_time_msg.stamp = get_clock()->now();
366368
processing_time_msg.data = processing_time_map["Total"];
367369
processing_time_publisher_->publish(processing_time_msg);

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,11 @@
2424
#include "rclcpp/rclcpp.hpp"
2525

2626
#include "autoware_control_msgs/msg/lateral.hpp"
27+
#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"
2728
#include "autoware_planning_msgs/msg/trajectory.hpp"
2829
#include "autoware_vehicle_msgs/msg/steering_report.hpp"
2930
#include "geometry_msgs/msg/pose.hpp"
3031
#include "nav_msgs/msg/odometry.hpp"
31-
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
3232

3333
#include <deque>
3434
#include <memory>
@@ -41,11 +41,11 @@ namespace autoware::motion::control::mpc_lateral_controller
4141

4242
using autoware::motion::control::trajectory_follower::LateralHorizon;
4343
using autoware_control_msgs::msg::Lateral;
44+
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;
4445
using autoware_planning_msgs::msg::Trajectory;
4546
using autoware_vehicle_msgs::msg::SteeringReport;
4647
using geometry_msgs::msg::Pose;
4748
using nav_msgs::msg::Odometry;
48-
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
4949

5050
using Eigen::MatrixXd;
5151
using Eigen::VectorXd;

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -26,13 +26,13 @@
2626
#include <diagnostic_updater/diagnostic_updater.hpp>
2727

2828
#include "autoware_control_msgs/msg/lateral.hpp"
29+
#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"
30+
#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp"
2931
#include "autoware_planning_msgs/msg/trajectory.hpp"
3032
#include "autoware_vehicle_msgs/msg/steering_report.hpp"
3133
#include "geometry_msgs/msg/pose.hpp"
3234
#include "geometry_msgs/msg/pose_stamped.hpp"
3335
#include "nav_msgs/msg/odometry.hpp"
34-
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
35-
#include "tier4_debug_msgs/msg/float32_stamped.hpp"
3636

3737
#include <deque>
3838
#include <memory>
@@ -45,11 +45,11 @@ namespace autoware::motion::control::mpc_lateral_controller
4545

4646
namespace trajectory_follower = ::autoware::motion::control::trajectory_follower;
4747
using autoware_control_msgs::msg::Lateral;
48+
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;
49+
using autoware_internal_debug_msgs::msg::Float32Stamped;
4850
using autoware_planning_msgs::msg::Trajectory;
4951
using autoware_vehicle_msgs::msg::SteeringReport;
5052
using nav_msgs::msg::Odometry;
51-
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
52-
using tier4_debug_msgs::msg::Float32Stamped;
5353
using trajectory_follower::LateralHorizon;
5454

5555
class MpcLateralController : public trajectory_follower::LateralControllerBase

control/autoware_mpc_lateral_controller/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<buildtool_depend>autoware_cmake</buildtool_depend>
2020

2121
<depend>autoware_control_msgs</depend>
22+
<depend>autoware_internal_debug_msgs</depend>
2223
<depend>autoware_interpolation</depend>
2324
<depend>autoware_motion_utils</depend>
2425
<depend>autoware_osqp_interface</depend>
@@ -36,7 +37,6 @@
3637
<depend>std_msgs</depend>
3738
<depend>tf2</depend>
3839
<depend>tf2_ros</depend>
39-
<depend>tier4_debug_msgs</depend>
4040

4141
<test_depend>ament_cmake_ros</test_depend>
4242
<test_depend>ament_lint_auto</test_depend>

control/autoware_mpc_lateral_controller/test/test_mpc.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -24,11 +24,11 @@
2424
#include <autoware/trajectory_follower_base/control_horizon.hpp>
2525

2626
#include "autoware_control_msgs/msg/lateral.hpp"
27+
#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"
2728
#include "autoware_planning_msgs/msg/trajectory.hpp"
2829
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
2930
#include "autoware_vehicle_msgs/msg/steering_report.hpp"
3031
#include "geometry_msgs/msg/pose.hpp"
31-
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
3232

3333
#ifdef ROS_DISTRO_GALACTIC
3434
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
@@ -45,12 +45,12 @@ namespace autoware::motion::control::mpc_lateral_controller
4545

4646
using autoware::motion::control::trajectory_follower::LateralHorizon;
4747
using autoware_control_msgs::msg::Lateral;
48+
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;
4849
using autoware_planning_msgs::msg::Trajectory;
4950
using autoware_planning_msgs::msg::TrajectoryPoint;
5051
using autoware_vehicle_msgs::msg::SteeringReport;
5152
using geometry_msgs::msg::Pose;
5253
using geometry_msgs::msg::PoseStamped;
53-
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
5454

5555
TrajectoryPoint makePoint(const double x, const double y, const float vx)
5656
{

0 commit comments

Comments
 (0)