Skip to content

Commit

Permalink
feat(emergency_goal_manager): change service for route selector
Browse files Browse the repository at this point in the history
Signed-off-by: Makoto Kurihara <[email protected]>
  • Loading branch information
mkuri committed Apr 4, 2024
1 parent 9e75f1b commit bcbb83d
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/srv/clear_route.hpp>
#include <autoware_adapi_v1_msgs/srv/set_route_points.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <std_srvs/srv/trigger.hpp>
#include <tier4_planning_msgs/srv/clear_route.hpp>
#include <tier4_planning_msgs/srv/set_waypoint_route.hpp>
#include <tier4_system_msgs/msg/emergency_goals_clear_command.hpp>
#include <tier4_system_msgs/msg/emergency_goals_stamped.hpp>

Expand All @@ -36,8 +36,8 @@ class EmergencyGoalManager : public rclcpp::Node
EmergencyGoalManager();

private:
using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints;
using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute;
using SetWaypointRoute = tier4_planning_msgs::srv::SetWaypointRoute;
using ClearRoute = tier4_planning_msgs::srv::ClearRoute;

// Subscriber
rclcpp::Subscription<tier4_system_msgs::msg::EmergencyGoalsStamped>::SharedPtr
Expand All @@ -51,7 +51,7 @@ class EmergencyGoalManager : public rclcpp::Node

// Client
rclcpp::CallbackGroup::SharedPtr client_set_mrm_route_points_callback_group_;
rclcpp::Client<SetRoutePoints>::SharedPtr client_set_mrm_route_points_;
rclcpp::Client<SetWaypointRoute>::SharedPtr client_set_mrm_route_points_;
rclcpp::CallbackGroup::SharedPtr client_clear_mrm_route_callback_group_;
rclcpp::Client<ClearRoute>::SharedPtr client_clear_mrm_route_;

Expand Down
2 changes: 1 addition & 1 deletion system/emergency_goal_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>rclcpp_components</depend>
<depend>std_srvs</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_system_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@ EmergencyGoalManager::EmergencyGoalManager() : Node("emergency_goal_manager")
// Client
client_set_mrm_route_points_callback_group_ =
create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
client_set_mrm_route_points_ = create_client<SetRoutePoints>(
"/planning/mission_planning/mission_planner/srv/set_mrm_route",
client_set_mrm_route_points_ = create_client<SetWaypointRoute>(
"/planning/mission_planning/route_selector/mrm/set_waypoint_route",
rmw_qos_profile_services_default, client_set_mrm_route_points_callback_group_);
client_clear_mrm_route_callback_group_ =
create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
client_clear_mrm_route_ = create_client<ClearRoute>(
"/planning/mission_planning/mission_planner/srv/clear_mrm_route",
"/planning/mission_planning/route_selector/mrm/clear_route",
rmw_qos_profile_services_default, client_clear_mrm_route_callback_group_);

// Initialize
Expand Down Expand Up @@ -76,10 +76,10 @@ void EmergencyGoalManager::onEmergencyGoalsClearCommand(

void EmergencyGoalManager::callSetMrmRoutePoints()
{
auto request = std::make_shared<SetRoutePoints::Request>();
auto request = std::make_shared<SetWaypointRoute::Request>();
request->header.frame_id = "map";
request->header.stamp = this->now();
request->option.allow_goal_modification = true;
request->allow_modification = true;

while (!emergency_goals_map_.empty()) {
// TODO(Makoto Kurihara): set goals with the highest priority
Expand All @@ -92,7 +92,7 @@ void EmergencyGoalManager::callSetMrmRoutePoints()
continue;
}

request->goal = goal_queue.front();
request->goal_pose = goal_queue.front();
goal_queue.pop();

auto future = client_set_mrm_route_points_->async_send_request(request);
Expand Down

0 comments on commit bcbb83d

Please sign in to comment.