moveit2
The MoveIt Motion Planning Framework for ROS 2.
execute_trajectory_action_capability.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, Kentaro Wada.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Kentaro Wada */
36 
38 
44 
45 namespace move_group
46 {
47 static const rclcpp::Logger LOGGER =
48  rclcpp::get_logger("moveit_move_group_default_capabilities.execute_trajectory_action_capability");
49 
51 {
52 }
53 
55 {
56  using std::placeholders::_1;
57  using std::placeholders::_2;
58 
59  auto node = context_->moveit_cpp_->getNode();
60  // start the move action server
61  execute_action_server_ = rclcpp_action::create_server<ExecTrajectory>(
62  node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(),
63  node->get_node_waitables_interface(), EXECUTE_ACTION_NAME,
64  [](const rclcpp_action::GoalUUID& /*unused*/, const std::shared_ptr<const ExecTrajectory::Goal>& /*unused*/) {
65  RCLCPP_INFO(LOGGER, "Received goal request");
66  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
67  },
68  [](const std::shared_ptr<ExecTrajectoryGoal>& /* unused */) {
69  RCLCPP_INFO(LOGGER, "Received request to cancel goal");
70  return rclcpp_action::CancelResponse::ACCEPT;
71  },
72  [this](const auto& goal) { executePathCallback(goal); });
73 }
74 
75 void MoveGroupExecuteTrajectoryAction::executePathCallback(const std::shared_ptr<ExecTrajectoryGoal>& goal)
76 {
77  auto action_res = std::make_shared<ExecTrajectory::Result>();
78  if (!context_->trajectory_execution_manager_)
79  {
80  const std::string response = "Cannot execute trajectory since ~allow_trajectory_execution was set to false";
81  action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
82  goal->abort(action_res);
83  return;
84  }
85 
86  executePath(goal, action_res);
87 
88  const std::string response = getActionResultString(action_res->error_code, false, false);
89  auto fb = std::make_shared<ExecTrajectory::Feedback>();
90  fb->state = response;
91  if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
92  {
93  goal->publish_feedback(fb);
94  goal->succeed(action_res);
95  }
96  else
97  {
98  goal->publish_feedback(fb);
99  goal->abort(action_res);
100  }
101 
102  setExecuteTrajectoryState(IDLE, goal);
103 }
104 
105 void MoveGroupExecuteTrajectoryAction::executePath(const std::shared_ptr<ExecTrajectoryGoal>& goal,
106  std::shared_ptr<ExecTrajectory::Result>& action_res)
107 {
108  RCLCPP_INFO(LOGGER, "Execution request received");
109 
110  context_->trajectory_execution_manager_->clear();
111  if (context_->trajectory_execution_manager_->push(goal->get_goal()->trajectory))
112  {
113  setExecuteTrajectoryState(MONITOR, goal);
114  context_->trajectory_execution_manager_->execute();
115  moveit_controller_manager::ExecutionStatus status = context_->trajectory_execution_manager_->waitForExecution();
117  {
118  action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
119  }
121  {
122  action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
123  }
125  {
126  action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
127  }
128  else
129  {
130  action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
131  }
132  RCLCPP_INFO_STREAM(LOGGER, "Execution completed: " << status.asString());
133  }
134  else
135  {
136  action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
137  }
138 }
139 
140 void MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback()
141 {
142  context_->trajectory_execution_manager_->stopExecution(true);
143 }
144 
145 void MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState(MoveGroupState state,
146  const std::shared_ptr<ExecTrajectoryGoal>& goal)
147 {
148  auto execute_feedback = std::make_shared<ExecTrajectory::Feedback>();
149  execute_feedback->state = stateToStr(state);
150  goal->publish_feedback(execute_feedback);
151 }
152 
153 } // namespace move_group
154 
155 #include <pluginlib/class_list_macros.hpp>
156 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
std::string getActionResultString(const moveit_msgs::msg::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
std::string stateToStr(MoveGroupState state) const
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::string asString() const
Convert the execution status to a string.