From 2022556c891e083a5e6f6ab560fc1c7813d0ec83 Mon Sep 17 00:00:00 2001 From: kyoichi-sugahara Date: Tue, 27 Aug 2024 18:34:57 +0900 Subject: [PATCH] Revert "feat: Add alive service to mission planner" This reverts commit 064c0086b9f4e6e431f006c9e689a486b10998d2. --- .../mission_planner/mission_planner_base.hpp | 8 -------- .../mission_planner/lib/mission_planner_base.cpp | 14 -------------- planning/mission_planner/package.xml | 1 - 3 files changed, 23 deletions(-) diff --git a/planning/mission_planner/include/mission_planner/mission_planner_base.hpp b/planning/mission_planner/include/mission_planner/mission_planner_base.hpp index 3aa0b5c39daa2..c7c56479f3f2f 100644 --- a/planning/mission_planner/include/mission_planner/mission_planner_base.hpp +++ b/planning/mission_planner/include/mission_planner/mission_planner_base.hpp @@ -15,9 +15,6 @@ #ifndef MISSION_PLANNER__MISSION_PLANNER_BASE_HPP_ #define MISSION_PLANNER__MISSION_PLANNER_BASE_HPP_ -#include - -#include #include #include @@ -64,11 +61,6 @@ class MissionPlanner : public rclcpp::Node tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; - rclcpp::Service::SharedPtr alive_service_; - void handleAliveService( - const std::shared_ptr request, - std::shared_ptr response); - bool getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose); void goalPoseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr); void checkpointCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr); diff --git a/planning/mission_planner/lib/mission_planner_base.cpp b/planning/mission_planner/lib/mission_planner_base.cpp index 7a9cf219ecb58..5a1551a156784 100644 --- a/planning/mission_planner/lib/mission_planner_base.cpp +++ b/planning/mission_planner/lib/mission_planner_base.cpp @@ -47,11 +47,6 @@ MissionPlanner::MissionPlanner( create_publisher("output/route", durable_qos); marker_publisher_ = create_publisher("debug/route_marker", durable_qos); - - alive_service_ = create_service( - "/planning/mission_planner/alive", - std::bind( - &MissionPlanner::handleAliveService, this, std::placeholders::_1, std::placeholders::_2)); } bool MissionPlanner::getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose) @@ -139,15 +134,6 @@ void MissionPlanner::checkpointCallback( publishRoute(route); } -void MissionPlanner::handleAliveService( - const std::shared_ptr request, - std::shared_ptr response) -{ - (void)request; - response->success = true; - response->message = "MissionPlanner is alive and running."; -} - void MissionPlanner::publishRoute(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const { if (!route.segments.empty()) { diff --git a/planning/mission_planner/package.xml b/planning/mission_planner/package.xml index 68d0d6fe1c3e8..f42875b759788 100644 --- a/planning/mission_planner/package.xml +++ b/planning/mission_planner/package.xml @@ -19,7 +19,6 @@ route_handler tf2_geometry_msgs tf2_ros - std_srvs ament_lint_auto autoware_lint_common