From 515627ab5121ac7bb36e02246bd218874471dc71 Mon Sep 17 00:00:00 2001 From: "David V. Lu" Date: Thu, 14 Apr 2022 14:30:29 -0400 Subject: [PATCH] Your future hasn't been written yet, no one's has. Your future is whatever you make it, so make it a good one. --- .../src/hybrid_planning_manager.cpp | 6 ++---- .../move_group_interface/src/move_group_interface.cpp | 10 +++------- 2 files changed, 5 insertions(+), 11 deletions(-) diff --git a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp index 87f142551c..dbe5d4cc71 100644 --- a/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp +++ b/moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/src/hybrid_planning_manager.cpp @@ -212,8 +212,7 @@ bool HybridPlanningManager::sendGlobalPlannerAction() // Add goal response callback global_goal_options.goal_response_callback = - [this](std::shared_future::SharedPtr> future) { - auto const& goal_handle = future.get(); + [this](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { auto planning_progress = std::make_shared(); auto& feedback = planning_progress->feedback; if (!goal_handle) @@ -283,8 +282,7 @@ bool HybridPlanningManager::sendLocalPlannerAction() // Add goal response callback local_goal_options.goal_response_callback = - [this](std::shared_future::SharedPtr> future) { - auto const& goal_handle = future.get(); + [this](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { auto planning_progress = std::make_shared(); auto& feedback = planning_progress->feedback; if (!goal_handle) diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index 0e2d80e09b..c9898f5e62 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -762,8 +762,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl auto send_goal_opts = rclcpp_action::Client::SendGoalOptions(); send_goal_opts.goal_response_callback = - [&](std::shared_future::SharedPtr> future) { - const auto& goal_handle = future.get(); + [&](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { if (!goal_handle) { done = true; @@ -841,8 +840,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl auto send_goal_opts = rclcpp_action::Client::SendGoalOptions(); send_goal_opts.goal_response_callback = - [&](std::shared_future::SharedPtr> future) { - const auto& goal_handle = future.get(); + [&](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { if (!goal_handle) { done = true; @@ -906,9 +904,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl auto send_goal_opts = rclcpp_action::Client::SendGoalOptions(); send_goal_opts.goal_response_callback = - [&](std::shared_future::SharedPtr> - future) { - const auto& goal_handle = future.get(); + [&](rclcpp_action::ClientGoalHandle::SharedPtr goal_handle) { if (!goal_handle) { done = true;