Skip to content

Commit

Permalink
feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil…
Browse files Browse the repository at this point in the history
…es evaluator/autoware_control_evaluator

Signed-off-by: vish0012 <[email protected]>
  • Loading branch information
vish0012 committed Jan 8, 2025
1 parent 1586372 commit c53b033
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@
#include <rclcpp/rclcpp.hpp>

#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>

Expand Down Expand Up @@ -85,7 +85,8 @@ class ControlEvaluatorNode : public rclcpp::Node
LaneletMapBin, autoware::universe_utils::polling_policy::Newest>
vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()};

rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr processing_time_pub_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
processing_time_pub_;
rclcpp::Publisher<MetricArrayMsg>::SharedPtr metrics_pub_;

// update Route Handler
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ ControlEvaluatorNode::ControlEvaluatorNode(const rclcpp::NodeOptions & node_opti
using std::placeholders::_1;

// Publisher
processing_time_pub_ =
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
processing_time_pub_ = this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"~/debug/processing_time_ms", 1);
metrics_pub_ = create_publisher<MetricArrayMsg>("~/metrics", 1);

// Parameters
Expand Down Expand Up @@ -288,7 +288,7 @@ void ControlEvaluatorNode::onTimer()
metrics_msg_ = MetricArrayMsg{};

// Publish processing time
tier4_debug_msgs::msg::Float64Stamped processing_time_msg;
autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg;
processing_time_msg.stamp = get_clock()->now();
processing_time_msg.data = stop_watch.toc();
processing_time_pub_->publish(processing_time_msg);
Expand Down

0 comments on commit c53b033

Please sign in to comment.