moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
45
46namespace move_group
47{
48namespace
49{
50rclcpp::Logger getLogger()
51{
52 return moveit::getLogger("moveit.ros.move_group.clear_octomap_service");
53}
54} // namespace
55
59
61{
62 callback_executor_.cancel();
63
64 if (callback_thread_.joinable())
65 callback_thread_.join();
66}
67
69{
70 auto node = context_->moveit_cpp_->getNode();
71 callback_group_ = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
72 false /* don't spin with node executor */);
73 callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
74 callback_thread_ = std::thread([this]() { callback_executor_.spin(); });
75 // start the move action server
76 execute_action_server_ = rclcpp_action::create_server<ExecTrajectory>(
77 node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(),
78 node->get_node_waitables_interface(), EXECUTE_ACTION_NAME,
79 [](const rclcpp_action::GoalUUID& /*unused*/, const std::shared_ptr<const ExecTrajectory::Goal>& /*unused*/) {
80 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
81 },
82 [](const std::shared_ptr<ExecTrajectoryGoal>& /* unused */) { return rclcpp_action::CancelResponse::ACCEPT; },
83 [this](const auto& goal) { executePathCallback(goal); }, rcl_action_server_get_default_options(),
84 callback_group_);
85}
86
87void MoveGroupExecuteTrajectoryAction::executePathCallback(const std::shared_ptr<ExecTrajectoryGoal>& goal)
88{
89 auto action_res = std::make_shared<ExecTrajectory::Result>();
90 if (!context_->trajectory_execution_manager_)
91 {
92 const std::string response = "Cannot execute trajectory since ~allow_trajectory_execution was set to false";
93 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
94 goal->abort(action_res);
95 return;
96 }
97
98 executePath(goal, action_res);
99
100 const std::string response = getActionResultString(action_res->error_code, false, false);
101 auto fb = std::make_shared<ExecTrajectory::Feedback>();
102 fb->state = response;
103 if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
104 {
105 goal->publish_feedback(fb);
106 goal->succeed(action_res);
107 }
108 else
109 {
110 goal->publish_feedback(fb);
111 goal->abort(action_res);
112 }
113
114 setExecuteTrajectoryState(IDLE, goal);
115}
116
117void MoveGroupExecuteTrajectoryAction::executePath(const std::shared_ptr<ExecTrajectoryGoal>& goal,
118 std::shared_ptr<ExecTrajectory::Result>& action_res)
119{
120 RCLCPP_INFO(getLogger(), "Execution request received");
121
122 if (context_->trajectory_execution_manager_->push(goal->get_goal()->trajectory, goal->get_goal()->controller_names))
123 {
124 setExecuteTrajectoryState(MONITOR, goal);
125 context_->trajectory_execution_manager_->execute();
126 moveit_controller_manager::ExecutionStatus status = context_->trajectory_execution_manager_->waitForExecution();
128 {
129 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
130 }
132 {
133 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
134 }
136 {
137 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
138 }
139 else
140 {
141 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
142 }
143 RCLCPP_INFO_STREAM(getLogger(), "Execution completed: " << status.asString());
144 }
145 else
146 {
147 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
148 }
149}
150
151void MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback()
152{
153 context_->trajectory_execution_manager_->stopExecution(true);
154}
155
156void MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState(MoveGroupState state,
157 const std::shared_ptr<ExecTrajectoryGoal>& goal)
158{
159 auto execute_feedback = std::make_shared<ExecTrajectory::Feedback>();
160 execute_feedback->state = stateToStr(state);
161 goal->publish_feedback(execute_feedback);
162}
163
164} // namespace move_group
165
166#include <pluginlib/class_list_macros.hpp>
167
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::string asString() const
Convert the execution status to a string.