Skip to content

Commit a209b13

Browse files
vish0012esteve
authored andcommitted
feat(autoware_costmap_generator): tier4_debug_msgs changed to autoware_internal-debug_msgs in autoware_costmap_generator (autowarefoundation#9901)
feat: tier4_debug_msgs changed to autoware_internal-debug_msgs in files planning/autoware_costmap_generator Signed-off-by: vish0012 <[email protected]>
1 parent 1831097 commit a209b13

File tree

2 files changed

+7
-5
lines changed

2 files changed

+7
-5
lines changed

planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -58,10 +58,10 @@
5858
#include <grid_map_ros/grid_map_ros.hpp>
5959
#include <rclcpp/rclcpp.hpp>
6060

61+
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
6162
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
6263
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
6364
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
64-
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
6565
#include <tier4_planning_msgs/msg/scenario.hpp>
6666

6767
#include <grid_map_msgs/msg/grid_map.h>
@@ -99,7 +99,8 @@ class CostmapGenerator : public rclcpp::Node
9999
rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr pub_costmap_;
100100
rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr pub_occupancy_grid_;
101101
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr pub_processing_time_;
102-
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_ms_;
102+
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
103+
pub_processing_time_ms_;
103104

104105
rclcpp::Subscription<autoware_map_msgs::msg::LaneletMapBin>::SharedPtr sub_lanelet_bin_map_;
105106
autoware::universe_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>

planning/autoware_costmap_generator/src/costmap_generator.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -176,7 +176,8 @@ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & node_options)
176176
create_publisher<autoware::universe_utils::ProcessingTimeDetail>("processing_time", 1);
177177
time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(pub_processing_time_);
178178
pub_processing_time_ms_ =
179-
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
179+
this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
180+
"~/debug/processing_time_ms", 1);
180181

181182
// Timer
182183
const auto period_ns = rclcpp::Rate(param_->update_rate).period();
@@ -269,7 +270,7 @@ void CostmapGenerator::onTimer()
269270

270271
if (!isActive()) {
271272
// Publish ProcessingTime
272-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
273+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
273274
processing_time_msg.stamp = get_clock()->now();
274275
processing_time_msg.data = stop_watch.toc();
275276
pub_processing_time_ms_->publish(processing_time_msg);
@@ -485,7 +486,7 @@ void CostmapGenerator::publishCostmap(
485486
pub_costmap_->publish(*out_gridmap_msg);
486487

487488
// Publish ProcessingTime
488-
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
489+
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
489490
processing_time_msg.stamp = get_clock()->now();
490491
processing_time_msg.data = stop_watch.toc();
491492
pub_processing_time_ms_->publish(processing_time_msg);

0 commit comments

Comments
 (0)