Skip to content

Commit

Permalink
Revert "feat: Add alive service to mission planner"
Browse files Browse the repository at this point in the history
This reverts commit 064c008.
  • Loading branch information
kyoichi-sugahara committed Aug 30, 2024
1 parent 1898549 commit 2022556
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,6 @@
#ifndef MISSION_PLANNER__MISSION_PLANNER_BASE_HPP_
#define MISSION_PLANNER__MISSION_PLANNER_BASE_HPP_

#include <std_srvs/srv/trigger.hpp>

#include <memory>
#include <string>
#include <vector>

Expand Down Expand Up @@ -64,11 +61,6 @@ class MissionPlanner : public rclcpp::Node
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr alive_service_;
void handleAliveService(
const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
std::shared_ptr<std_srvs::srv::Trigger::Response> 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);
Expand Down
14 changes: 0 additions & 14 deletions planning/mission_planner/lib/mission_planner_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,6 @@ MissionPlanner::MissionPlanner(
create_publisher<autoware_auto_planning_msgs::msg::HADMapRoute>("output/route", durable_qos);
marker_publisher_ =
create_publisher<visualization_msgs::msg::MarkerArray>("debug/route_marker", durable_qos);

alive_service_ = create_service<std_srvs::srv::Trigger>(
"/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)
Expand Down Expand Up @@ -139,15 +134,6 @@ void MissionPlanner::checkpointCallback(
publishRoute(route);
}

void MissionPlanner::handleAliveService(
const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
std::shared_ptr<std_srvs::srv::Trigger::Response> 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()) {
Expand Down
1 change: 0 additions & 1 deletion planning/mission_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
<depend>route_handler</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>std_srvs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down

0 comments on commit 2022556

Please sign in to comment.