diff --git a/moveit_ros/move_group/src/move_group.cpp b/moveit_ros/move_group/src/move_group.cpp index e67ad74963..425b98192c 100644 --- a/moveit_ros/move_group/src/move_group.cpp +++ b/moveit_ros/move_group/src/move_group.cpp @@ -309,7 +309,7 @@ int main(int argc, char** argv) RCLCPP_INFO(nh->get_logger(), "MoveGroup debug mode is OFF"); } - rclcpp::executors::MultiThreadedExecutor executor; + rclcpp::executors::SingleThreadedExecutor executor; move_group::MoveGroupExe mge(moveit_cpp, default_planning_pipeline, debug); diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index 8a863ef80d..8cc1059450 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -193,12 +193,13 @@ void TrajectoryExecutionManager::initialize() // The default callback group for rclcpp::Node is MutuallyExclusive which means we cannot call // receiveEvent while processing a different callback. To fix this we create a new callback group (the type is not // important since we only use it to process one callback) and associate event_topic_subscriber_ with this callback group - auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); auto options = rclcpp::SubscriptionOptions(); options.callback_group = callback_group; event_topic_subscriber_ = node_->create_subscription( EXECUTION_EVENT_TOPIC, rclcpp::SystemDefaultsQoS(), [this](const std_msgs::msg::String::ConstSharedPtr& event) { return receiveEvent(event); }, options); + private_executor_->add_callback_group(callback_group, node_->get_node_base_interface()); controller_mgr_node_->get_parameter("trajectory_execution.execution_duration_monitoring", execution_duration_monitoring_); diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index f3c7b6f506..44d191fe8d 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -192,18 +192,22 @@ class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface unsigned int getVariableCount() const; /** \brief Get the descriptions of all planning plugins loaded by the action server */ - bool getInterfaceDescriptions(std::vector& desc) const; + bool getInterfaceDescriptions(std::vector& desc, + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1)) const; /** \brief Get the description of the default planning plugin loaded by the action server */ - bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const; + bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc, + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1)) const; /** \brief Get the planner parameters for given group and planner_id */ - std::map getPlannerParams(const std::string& planner_id, - const std::string& group = "") const; + std::map + getPlannerParams(const std::string& planner_id, const std::string& group = "", + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1)) const; /** \brief Set the planner parameters for given group and planner_id */ void setPlannerParams(const std::string& planner_id, const std::string& group, - const std::map& params, bool bReplace = false); + const std::map& params, bool bReplace = false, + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1)); std::string getDefaultPlanningPipelineId() const; @@ -690,9 +694,15 @@ class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface /**@{*/ /** \brief Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified - target. - This call is not blocking (does not wait for the execution of the trajectory to complete). */ - moveit::core::MoveItErrorCode asyncMove(); + * target. + * This call is not blocking (does not wait for the execution of the trajectory to complete). + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in case + * that server doesn't answer whether the request is accepted or rejected within certain period of time \param [in] + * moving_timeout period of time duration for waiting server's job to finish. Function returns TIME_OUT in case that + * server's job is not finished within certain period of time + */ + moveit::core::MoveItErrorCode asyncMove(const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& moving_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Get the move_group action client used by the \e MoveGroupInterface. The client can be used for querying the execution state of the trajectory and abort trajectory execution @@ -701,51 +711,90 @@ class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface rclcpp_action::Client& getMoveGroupClient() const; /** \brief Plan and execute a trajectory that takes the group of joints declared in the constructor to the specified - target. - This call is always blocking (waits for the execution of the trajectory to complete) and requires an asynchronous - spinner to be started.*/ - moveit::core::MoveItErrorCode move(); + * target. + * This call is always blocking (waits for the execution of the trajectory to complete) and requires an asynchronous + * spinner to be started. + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in case + * that server doesn't answer whether the request is accepted or rejected within certain period of time \param [in] + * moving_timeout period of time duration for waiting server's job to finish. Function returns TIME_OUT in case that + * server's job is not finished within certain period of time + */ + moveit::core::MoveItErrorCode move(const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& moving_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Compute a motion plan that takes the group declared in the constructor from the current state to the - specified - target. No execution is performed. The resulting plan is stored in \e plan*/ - moveit::core::MoveItErrorCode plan(Plan& plan); + * specified + * target. No execution is performed. The resulting plan is stored in \e plan + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in case + * that server doesn't answer whether the request is accepted or rejected within certain period of time \param [in] + * planning_timeout period of time duration for waiting server's job to finish. Function returns TIME_OUT in case that + * server's job is not finished within certain period of time + */ + moveit::core::MoveItErrorCode plan(Plan& plan, + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& planning_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Given a \e plan, execute it without waiting for completion. * \param [in] plan The motion plan for which to execute * \param [in] controllers An optional list of ros2_controllers to execute with. If none, MoveIt will attempt to find * a controller. The exact behavior of finding a controller depends on which MoveItControllerManager plugin is active. - * \return moveit::core::MoveItErrorCode::SUCCESS if successful + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in + * case that server doesn't answer whether the request is accepted or rejected within certain period of time \param + * [in] trajectory_execution_timeout period of time duration for waiting server's job to finish. Function returns + * TIME_OUT in case that server's job is not finished within certain period of time \return + * moveit::core::MoveItErrorCode::SUCCESS if successful */ - moveit::core::MoveItErrorCode asyncExecute(const Plan& plan, - const std::vector& controllers = std::vector()); + moveit::core::MoveItErrorCode + asyncExecute(const Plan& plan, const std::vector& controllers = std::vector(), + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& trajectory_execution_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Given a \e robot trajectory, execute it without waiting for completion. * \param [in] trajectory The trajectory to execute * \param [in] controllers An optional list of ros2_controllers to execute with. If none, MoveIt will attempt to find * a controller. The exact behavior of finding a controller depends on which MoveItControllerManager plugin is active. - * \return moveit::core::MoveItErrorCode::SUCCESS if successful + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in + * case that server doesn't answer whether the request is accepted or rejected within certain period of time \param + * [in] trajectory_execution_timeout period of time duration for waiting server's job to finish. Function returns + * TIME_OUT in case that server's job is not finished within certain period of time \return + * moveit::core::MoveItErrorCode::SUCCESS if successful */ - moveit::core::MoveItErrorCode asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory, - const std::vector& controllers = std::vector()); + moveit::core::MoveItErrorCode + asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory, + const std::vector& controllers = std::vector(), + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& trajectory_execution_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Given a \e plan, execute it while waiting for completion. * \param [in] plan Contains trajectory info as well as metadata such as a RobotModel. * \param [in] controllers An optional list of ros2_controllers to execute with. If none, MoveIt will attempt to find * a controller. The exact behavior of finding a controller depends on which MoveItControllerManager plugin is active. - * \return moveit::core::MoveItErrorCode::SUCCESS if successful + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in + * case that server doesn't answer whether the request is accepted or rejected within certain period of time \param + * [in] trajectory_execution_timeout period of time duration for waiting server's job to finish. Function returns + * TIME_OUT in case that server's job is not finished within certain period of time \return + * moveit::core::MoveItErrorCode::SUCCESS if successful */ - moveit::core::MoveItErrorCode execute(const Plan& plan, - const std::vector& controllers = std::vector()); + moveit::core::MoveItErrorCode + execute(const Plan& plan, const std::vector& controllers = std::vector(), + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& trajectory_execution_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Given a \e robot trajectory, execute it while waiting for completion. * \param [in] trajectory The trajectory to execute * \param [in] controllers An optional list of ros2_controllers to execute with. If none, MoveIt will attempt to find * a controller. The exact behavior of finding a controller depends on which MoveItControllerManager plugin is active. - * \return moveit::core::MoveItErrorCode::SUCCESS if successful + * \param [in] server_timeout period of time duration for waiting server's response. Function returns TIME_OUT in + * case that server doesn't answer whether the request is accepted or rejected within certain period of time \param + * [in] trajectory_execution_timeout period of time duration for waiting server's job to finish. Function returns + * TIME_OUT in case that server's job is not finished within certain period of time \return + * moveit::core::MoveItErrorCode::SUCCESS if successful */ - moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory, - const std::vector& controllers = std::vector()); + moveit::core::MoveItErrorCode + execute(const moveit_msgs::msg::RobotTrajectory& trajectory, + const std::vector& controllers = std::vector(), + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1), + const rclcpp::Duration& trajectory_execution_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Compute a Cartesian path that follows specified waypoints with a step size of at most \e eef_step meters between end effector configurations of consecutive points in the result \e trajectory. The reference frame for the @@ -758,7 +807,8 @@ class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface Return -1.0 in case of error. */ double computeCartesianPath(const std::vector& waypoints, double eef_step, double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory, - bool avoid_collisions = true, moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr); + bool avoid_collisions = true, moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr, + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Compute a Cartesian path that follows specified waypoints with a step size of at most \e eef_step meters between end effector configurations of consecutive points in the result \e trajectory. The reference frame for the @@ -775,7 +825,8 @@ class MOVEIT_MOVE_GROUP_INTERFACE_EXPORT MoveGroupInterface double computeCartesianPath(const std::vector& waypoints, double eef_step, double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory, const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions = true, - moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr); + moveit_msgs::msg::MoveItErrorCodes* error_code = nullptr, + const rclcpp::Duration& server_timeout = rclcpp::Duration::from_seconds(-1)); /** \brief Stop any trajectory execution, if one is active */ void stop(); 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 4f93f72781..de422a7f1d 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 @@ -113,11 +113,10 @@ class MoveGroupInterface::MoveGroupInterfaceImpl : opt_(opt), node_(node), logger_(moveit::getLogger("moveit.ros.move_group_interface")), tf_buffer_(tf_buffer) { // We have no control on how the passed node is getting executed. To make sure MGI is functional, we're creating - // our own callback group which is managed in a separate callback thread + // our own callback group which is managed in a separate executor callback_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false /* don't spin with node executor */); - callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface()); - callback_thread_ = std::thread([this]() { callback_executor_.spin(); }); + callback_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); robot_model_ = opt.robot_model ? opt.robot_model : getSharedRobotModel(node_, opt.robot_description); if (!getRobotModel()) @@ -200,9 +199,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl constraints_init_thread_->join(); callback_executor_.cancel(); - - if (callback_thread_.joinable()) - callback_thread_.join(); } const std::shared_ptr& getTF() const @@ -230,40 +226,55 @@ class MoveGroupInterface::MoveGroupInterfaceImpl return *move_action_client_; } - bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) + bool getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc, + const rclcpp::Duration& server_timeout) { auto req = std::make_shared(); auto future_response = query_service_->async_send_request(req); - if (future_response.valid()) + if (callback_executor_.spin_until_future_complete(future_response, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) { - const auto& response = future_response.get(); - if (!response->planner_interfaces.empty()) - { - desc = response->planner_interfaces.front(); - return true; - } + RCLCPP_ERROR(logger_, "MoveGroupInterfaceImpl::getInterfaceDescription() get sent call failed :("); + return false; } + + const auto& response = future_response.get(); + if (!response->planner_interfaces.empty()) + { + desc = response->planner_interfaces.front(); + return true; + } + return false; } - bool getInterfaceDescriptions(std::vector& desc) + bool getInterfaceDescriptions(std::vector& desc, + const rclcpp::Duration& server_timeout) { auto req = std::make_shared(); auto future_response = query_service_->async_send_request(req); - if (future_response.valid()) + + if (callback_executor_.spin_until_future_complete(future_response, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) { - const auto& response = future_response.get(); - if (!response->planner_interfaces.empty()) - { - desc = response->planner_interfaces; - return true; - } + RCLCPP_ERROR(logger_, "MoveGroupInterfaceImpl::getInterfaceDescriptions() get sent call failed :("); + return false; + } + + const auto& response = future_response.get(); + if (!response->planner_interfaces.empty()) + { + desc = response->planner_interfaces; + return true; } return false; } - std::map getPlannerParams(const std::string& planner_id, const std::string& group = "") + std::map getPlannerParams(const std::string& planner_id, const std::string& group, + const rclcpp::Duration& server_timeout) { auto req = std::make_shared(); moveit_msgs::srv::GetPlannerParams::Response::SharedPtr response; @@ -272,17 +283,24 @@ class MoveGroupInterface::MoveGroupInterfaceImpl std::map result; auto future_response = get_params_service_->async_send_request(req); - if (future_response.valid()) + + if (callback_executor_.spin_until_future_complete(future_response, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) { - response = future_response.get(); - for (unsigned int i = 0, end = response->params.keys.size(); i < end; ++i) - result[response->params.keys[i]] = response->params.values[i]; + RCLCPP_ERROR(logger_, "MoveGroupInterfaceImpl::getPlannerParams() get sent call failed :("); + return result; } + + response = future_response.get(); + for (unsigned int i = 0, end = response->params.keys.size(); i < end; ++i) + result[response->params.keys[i]] = response->params.values[i]; return result; } void setPlannerParams(const std::string& planner_id, const std::string& group, - const std::map& params, bool replace = false) + const std::map& params, bool replace, + const rclcpp::Duration& server_timeout) { auto req = std::make_shared(); req->planner_config = planner_id; @@ -293,7 +311,15 @@ class MoveGroupInterface::MoveGroupInterfaceImpl req->params.keys.push_back(param.first); req->params.values.push_back(param.second); } - set_params_service_->async_send_request(req); + + auto future_response = set_params_service_->async_send_request(req); + + if (callback_executor_.spin_until_future_complete(future_response, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_ERROR(logger_, "MoveGroupInterfaceImpl::setPlannerParams() get sent call failed :("); + } } std::string getDefaultPlanningPipelineId() const @@ -633,7 +659,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl return true; } - moveit::core::MoveItErrorCode plan(Plan& plan) + moveit::core::MoveItErrorCode plan(Plan& plan, const rclcpp::Duration& server_timeout, + const rclcpp::Duration& planning_timeout) { if (!move_action_client_ || !move_action_client_->action_server_is_ready()) { @@ -650,7 +677,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl goal.planning_options.planning_scene_diff.is_diff = true; goal.planning_options.planning_scene_diff.robot_state.is_diff = true; - bool done = false; rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN; std::shared_ptr res; auto send_goal_opts = rclcpp_action::Client::SendGoalOptions(); @@ -659,7 +685,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl [&](const rclcpp_action::ClientGoalHandle::SharedPtr& goal_handle) { if (!goal_handle) { - done = true; RCLCPP_INFO(logger_, "Planning request rejected"); } else @@ -669,7 +694,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl [&](const rclcpp_action::ClientGoalHandle::WrappedResult& result) { res = result.result; code = result.code; - done = true; switch (result.code) { @@ -689,11 +713,21 @@ class MoveGroupInterface::MoveGroupInterfaceImpl }; auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts); + if (callback_executor_.spin_until_future_complete(goal_handle_future, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_ERROR(logger_, "MoveGroupInterfaceImpl::plan() get sent call failed :("); + return moveit::core::MoveItErrorCode::TIMED_OUT; + } - // wait until send_goal_opts.result_callback is called - while (!done) + auto goal_result_future = move_action_client_->async_get_result(goal_handle_future.get()); + if (callback_executor_.spin_until_future_complete(goal_result_future, + planning_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) { - std::this_thread::sleep_for(std::chrono::milliseconds(1)); + RCLCPP_ERROR(logger_, "MoveGroupInterface::plan() get result call failed :("); + return moveit::core::MoveItErrorCode::TIMED_OUT; } if (code != rclcpp_action::ResultCode::SUCCEEDED) @@ -710,7 +744,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl return res->error_code; } - moveit::core::MoveItErrorCode move(bool wait) + moveit::core::MoveItErrorCode move(bool wait, const rclcpp::Duration& server_timeout, + const rclcpp::Duration& moving_timeout) { if (!move_action_client_ || !move_action_client_->action_server_is_ready()) { @@ -727,7 +762,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl goal.planning_options.planning_scene_diff.is_diff = true; goal.planning_options.planning_scene_diff.robot_state.is_diff = true; - bool done = false; rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN; std::shared_ptr res; auto send_goal_opts = rclcpp_action::Client::SendGoalOptions(); @@ -736,7 +770,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl [&](const rclcpp_action::ClientGoalHandle::SharedPtr& goal_handle) { if (!goal_handle) { - done = true; RCLCPP_INFO(logger_, "Plan and Execute request rejected"); } else @@ -746,7 +779,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl [&](const rclcpp_action::ClientGoalHandle::WrappedResult& result) { res = result.result; code = result.code; - done = true; switch (result.code) { @@ -764,14 +796,26 @@ class MoveGroupInterface::MoveGroupInterfaceImpl return; } }; + auto goal_handle_future = move_action_client_->async_send_goal(goal, send_goal_opts); + if (callback_executor_.spin_until_future_complete(goal_handle_future, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_ERROR(logger_, "MoveGroupInterface::move() get sent call failed :("); + return moveit::core::MoveItErrorCode::TIMED_OUT; + } + if (!wait) return moveit::core::MoveItErrorCode::SUCCESS; - // wait until send_goal_opts.result_callback is called - while (!done) + auto goal_result_future = move_action_client_->async_get_result(goal_handle_future.get()); + if (callback_executor_.spin_until_future_complete(goal_result_future, + moving_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) { - std::this_thread::sleep_for(std::chrono::milliseconds(1)); + RCLCPP_ERROR(logger_, "MoveGroupInterface::move() get result call failed :("); + return moveit::core::MoveItErrorCode::TIMED_OUT; } if (code != rclcpp_action::ResultCode::SUCCEEDED) @@ -782,7 +826,9 @@ class MoveGroupInterface::MoveGroupInterfaceImpl } moveit::core::MoveItErrorCode execute(const moveit_msgs::msg::RobotTrajectory& trajectory, bool wait, - const std::vector& controllers = std::vector()) + const std::vector& controllers, + const rclcpp::Duration& server_timeout, + const rclcpp::Duration& trajectory_execution_timeout) { if (!execute_action_client_ || !execute_action_client_->action_server_is_ready()) { @@ -790,7 +836,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl return moveit::core::MoveItErrorCode::FAILURE; } - bool done = false; rclcpp_action::ResultCode code = rclcpp_action::ResultCode::UNKNOWN; std::shared_ptr res; auto send_goal_opts = rclcpp_action::Client::SendGoalOptions(); @@ -799,7 +844,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl [&](const rclcpp_action::ClientGoalHandle::SharedPtr& goal_handle) { if (!goal_handle) { - done = true; RCLCPP_INFO(logger_, "Execute request rejected"); } else @@ -809,7 +853,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl [&](const rclcpp_action::ClientGoalHandle::WrappedResult& result) { res = result.result; code = result.code; - done = true; switch (result.code) { @@ -833,13 +876,24 @@ class MoveGroupInterface::MoveGroupInterfaceImpl goal.controller_names = controllers; auto goal_handle_future = execute_action_client_->async_send_goal(goal, send_goal_opts); + if (callback_executor_.spin_until_future_complete(goal_handle_future, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_ERROR(logger_, "MoveGroupInterface::execute() get sent call failed :("); + return moveit::core::MoveItErrorCode::TIMED_OUT; + } + if (!wait) return moveit::core::MoveItErrorCode::SUCCESS; - // wait until send_goal_opts.result_callback is called - while (!done) + auto goal_result_future = execute_action_client_->async_get_result(goal_handle_future.get()); + if (callback_executor_.spin_until_future_complete( + goal_result_future, trajectory_execution_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) { - std::this_thread::sleep_for(std::chrono::milliseconds(1)); + RCLCPP_ERROR(logger_, "MoveGroupInterface::execute() get result call failed :("); + return moveit::core::MoveItErrorCode::TIMED_OUT; } if (code != rclcpp_action::ResultCode::SUCCEEDED) @@ -852,7 +906,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl double computeCartesianPath(const std::vector& waypoints, double step, double jump_threshold, moveit_msgs::msg::RobotTrajectory& msg, const moveit_msgs::msg::Constraints& path_constraints, bool avoid_collisions, - moveit_msgs::msg::MoveItErrorCodes& error_code) + moveit_msgs::msg::MoveItErrorCodes& error_code, const rclcpp::Duration& server_timeout) { auto req = std::make_shared(); moveit_msgs::srv::GetCartesianPath::Response::SharedPtr response; @@ -879,6 +933,14 @@ class MoveGroupInterface::MoveGroupInterfaceImpl req->max_acceleration_scaling_factor = max_acceleration_scaling_factor_; auto future_response = cartesian_path_service_->async_send_request(req); + if (callback_executor_.spin_until_future_complete(future_response, + server_timeout.to_chrono>()) != + rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_ERROR(logger_, "MoveGroupInterface::computeCartesianPath() get sent call failed :("); + return -1.0; + } + if (future_response.valid()) { response = future_response.get(); @@ -1259,7 +1321,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl rclcpp::Logger logger_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_executor_; - std::thread callback_thread_; std::shared_ptr tf_buffer_; moveit::core::RobotModelConstPtr robot_model_; planning_scene_monitor::CurrentStateMonitorPtr current_state_monitor_; @@ -1379,26 +1440,30 @@ moveit::core::RobotModelConstPtr MoveGroupInterface::getRobotModel() const return impl_->getRobotModel(); } -bool MoveGroupInterface::getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc) const +bool MoveGroupInterface::getInterfaceDescription(moveit_msgs::msg::PlannerInterfaceDescription& desc, + const rclcpp::Duration& server_timeout) const { - return impl_->getInterfaceDescription(desc); + return impl_->getInterfaceDescription(desc, server_timeout); } -bool MoveGroupInterface::getInterfaceDescriptions(std::vector& desc) const +bool MoveGroupInterface::getInterfaceDescriptions(std::vector& desc, + const rclcpp::Duration& server_timeout) const { - return impl_->getInterfaceDescriptions(desc); + return impl_->getInterfaceDescriptions(desc, server_timeout); } std::map MoveGroupInterface::getPlannerParams(const std::string& planner_id, - const std::string& group) const + const std::string& group, + const rclcpp::Duration& server_timeout) const { - return impl_->getPlannerParams(planner_id, group); + return impl_->getPlannerParams(planner_id, group, server_timeout); } void MoveGroupInterface::setPlannerParams(const std::string& planner_id, const std::string& group, - const std::map& params, bool replace) + const std::map& params, bool replace, + const rclcpp::Duration& server_timeout) { - impl_->setPlannerParams(planner_id, group, params, replace); + impl_->setPlannerParams(planner_id, group, params, replace, server_timeout); } std::string MoveGroupInterface::getDefaultPlanningPipelineId() const @@ -1446,9 +1511,10 @@ void MoveGroupInterface::setMaxAccelerationScalingFactor(double max_acceleration impl_->setMaxAccelerationScalingFactor(max_acceleration_scaling_factor); } -moveit::core::MoveItErrorCode MoveGroupInterface::asyncMove() +moveit::core::MoveItErrorCode MoveGroupInterface::asyncMove(const rclcpp::Duration& server_timeout, + const rclcpp::Duration& moving_timeout) { - return impl_->move(false); + return impl_->move(false, server_timeout, moving_timeout); } rclcpp_action::Client& MoveGroupInterface::getMoveGroupClient() const @@ -1456,37 +1522,47 @@ rclcpp_action::Client& MoveGroupInterface::getMo return impl_->getMoveGroupClient(); } -moveit::core::MoveItErrorCode MoveGroupInterface::move() +moveit::core::MoveItErrorCode MoveGroupInterface::move(const rclcpp::Duration& server_timeout, + const rclcpp::Duration& moving_timeout) { - return impl_->move(true); + return impl_->move(true, server_timeout, moving_timeout); } moveit::core::MoveItErrorCode MoveGroupInterface::asyncExecute(const Plan& plan, - const std::vector& controllers) + const std::vector& controllers, + const rclcpp::Duration& server_timeout, + const rclcpp::Duration& trajectory_execution_timeout) { - return impl_->execute(plan.trajectory, false, controllers); + return impl_->execute(plan.trajectory, false, controllers, server_timeout, trajectory_execution_timeout); } moveit::core::MoveItErrorCode MoveGroupInterface::asyncExecute(const moveit_msgs::msg::RobotTrajectory& trajectory, - const std::vector& controllers) + const std::vector& controllers, + const rclcpp::Duration& server_timeout, + const rclcpp::Duration& trajectory_execution_timeout) { - return impl_->execute(trajectory, false, controllers); + return impl_->execute(trajectory, false, controllers, server_timeout, trajectory_execution_timeout); } -moveit::core::MoveItErrorCode MoveGroupInterface::execute(const Plan& plan, const std::vector& controllers) +moveit::core::MoveItErrorCode MoveGroupInterface::execute(const Plan& plan, const std::vector& controllers, + const rclcpp::Duration& server_timeout, + const rclcpp::Duration& trajectory_execution_timeout) { - return impl_->execute(plan.trajectory, true, controllers); + return impl_->execute(plan.trajectory, true, controllers, server_timeout, trajectory_execution_timeout); } moveit::core::MoveItErrorCode MoveGroupInterface::execute(const moveit_msgs::msg::RobotTrajectory& trajectory, - const std::vector& controllers) + const std::vector& controllers, + const rclcpp::Duration& server_timeout, + const rclcpp::Duration& trajectory_execution_timeout) { - return impl_->execute(trajectory, true, controllers); + return impl_->execute(trajectory, true, controllers, server_timeout, trajectory_execution_timeout); } -moveit::core::MoveItErrorCode MoveGroupInterface::plan(Plan& plan) +moveit::core::MoveItErrorCode MoveGroupInterface::plan(Plan& plan, const rclcpp::Duration& server_timeout, + const rclcpp::Duration& planning_timeout) { - return impl_->plan(plan); + return impl_->plan(plan, server_timeout, planning_timeout); } // moveit_msgs::action::Pickup::Goal MoveGroupInterface::constructPickupGoal(const std::string& object, @@ -1531,22 +1607,24 @@ moveit::core::MoveItErrorCode MoveGroupInterface::plan(Plan& plan) double MoveGroupInterface::computeCartesianPath(const std::vector& waypoints, double eef_step, double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory, - bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code) + bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code, + const rclcpp::Duration& server_timeout) { moveit_msgs::msg::Constraints path_constraints_tmp; return computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory, moveit_msgs::msg::Constraints(), - avoid_collisions, error_code); + avoid_collisions, error_code, server_timeout); } double MoveGroupInterface::computeCartesianPath(const std::vector& waypoints, double eef_step, double jump_threshold, moveit_msgs::msg::RobotTrajectory& trajectory, const moveit_msgs::msg::Constraints& path_constraints, - bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code) + bool avoid_collisions, moveit_msgs::msg::MoveItErrorCodes* error_code, + const rclcpp::Duration& server_timeout) { if (error_code) { return impl_->computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory, path_constraints, - avoid_collisions, *error_code); + avoid_collisions, *error_code, server_timeout); } else { @@ -1554,7 +1632,7 @@ double MoveGroupInterface::computeCartesianPath(const std::vectorcomputeCartesianPath(waypoints, eef_step, jump_threshold, trajectory, path_constraints, - avoid_collisions, err); + avoid_collisions, err, server_timeout); } }