diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index fc68754059..8264be798a 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -138,7 +138,7 @@ class MoveItControllerHandle * Return true if the execution is complete (whether successful or not). * Return false if timeout was reached. * If timeout is -1 (default argument), wait until the execution is complete (no timeout). */ - virtual bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(-1)) = 0; + virtual bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration::from_nanoseconds(-1)) = 0; /** \brief Return the execution status of the last trajectory sent to the controller. */ virtual ExecutionStatus getLastExecutionStatus() = 0; diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index ec71aac3be..1c74b62a1c 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -150,7 +150,7 @@ class GripperControllerHandle : public ActionBasedControllerHandle::SendGoalOptions send_goal_options; // Active callback send_goal_options.goal_response_callback = - [this](std::shared_future::GoalHandle::SharedPtr> + [this](rclcpp_action::Client::GoalHandle::SharedPtr /* unused-arg */) { RCLCPP_DEBUG_STREAM(LOGGER, name_ << " started execution"); }; // Send goal auto current_goal_future = controller_action_client_->async_send_goal(goal, send_goal_options); diff --git a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp index 9c0b299402..ee26da5316 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp @@ -66,11 +66,8 @@ bool FollowJointTrajectoryControllerHandle::sendTrajectory(const moveit_msgs::ms rclcpp_action::Client::SendGoalOptions send_goal_options; // Active callback send_goal_options.goal_response_callback = - [this]( - std::shared_future::GoalHandle::SharedPtr> - future) { + [this](rclcpp_action::Client::GoalHandle::SharedPtr goal_handle) { RCLCPP_INFO_STREAM(LOGGER, name_ << " started execution"); - const auto& goal_handle = future.get(); if (!goal_handle) RCLCPP_WARN(LOGGER, "Goal request rejected"); else 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;