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 planning/autoware_mission_planner

Signed-off-by: vish0012 <vishalchhn42@gmail.com>
  • Loading branch information
vish0012 committed Jan 14, 2025
1 parent 1586372 commit 6977477
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -87,14 +87,14 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options)
is_mission_planner_ready_ = false;

logger_configure_ = std::make_unique<autoware::universe_utils::LoggerLevelConfigure>(this);
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);
}

void MissionPlanner::publish_processing_time(
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch)
{
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
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_adapi_v1_msgs/srv/set_route.hpp>
#include <autoware_adapi_v1_msgs/srv/set_route_points.hpp>
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_planning_msgs/msg/reroute_availability.hpp>
#include <tier4_planning_msgs/msg/route_state.hpp>
#include <tier4_planning_msgs/srv/clear_route.hpp>
Expand Down Expand Up @@ -146,7 +146,8 @@ class MissionPlanner : public rclcpp::Node
bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route);

std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
pub_processing_time_;
};

} // namespace autoware::mission_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,14 +138,14 @@ RouteSelector::RouteSelector(const rclcpp::NodeOptions & options)
main_request_ = std::monostate{};

// Processing time
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);
}

void RouteSelector::publish_processing_time(
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch)
{
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
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <tier4_debug_msgs/msg/float64_stamped.hpp>
#include <tier4_planning_msgs/msg/route_state.hpp>
#include <tier4_planning_msgs/srv/clear_route.hpp>
#include <tier4_planning_msgs/srv/set_lanelet_route.hpp>
Expand Down Expand Up @@ -82,7 +82,8 @@ class RouteSelector : public rclcpp::Node
rclcpp::Client<SetLaneletRoute>::SharedPtr cli_set_lanelet_route_;
rclcpp::Subscription<RouteState>::SharedPtr sub_state_;
rclcpp::Subscription<LaneletRoute>::SharedPtr sub_route_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float64Stamped>::SharedPtr pub_processing_time_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float64Stamped>::SharedPtr
pub_processing_time_;

bool initialized_;
bool mrm_operating_;
Expand Down

0 comments on commit 6977477

Please sign in to comment.