Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_surround_obstacle_checker): tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_surround_obstacle_checker #9915

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions planning/autoware_surround_obstacle_checker/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
"~/output/velocity_limit_clear_command", rclcpp::QoS{1}.transient_local());
pub_velocity_limit_ = this->create_publisher<VelocityLimit>(
"~/output/max_velocity", rclcpp::QoS{1}.transient_local());
pub_processing_time_ =
this->create_publisher<tier4_debug_msgs::msg::Float64Stamped>("~/debug/processing_time_ms", 1);
pub_processing_time_ = this->create_publisher<autoware_internal_debug_msgs::msg::Float64Stamped>(
"~/debug/processing_time_ms", 1);

using std::chrono_literals::operator""ms;
timer_ = rclcpp::create_timer(
Expand Down Expand Up @@ -231,7 +231,7 @@ void SurroundObstacleCheckerNode::onTimer()
debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart);
}

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();
pub_processing_time_->publish(processing_time_msg);
Expand Down
5 changes: 3 additions & 2 deletions planning/autoware_surround_obstacle_checker/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,12 @@
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <diagnostic_msgs/msg/key_value.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
Expand Down Expand Up @@ -106,7 +106,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
this, "~/input/objects"};
rclcpp::Publisher<VelocityLimitClearCommand>::SharedPtr pub_clear_velocity_limit_;
rclcpp::Publisher<VelocityLimit>::SharedPtr pub_velocity_limit_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
pub_processing_time_;

// parameter callback result
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
Expand Down
Loading