moveit2
The MoveIt Motion Planning Framework for ROS 2.
execute_trajectory_service_capability.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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: Ioan Sucan */
36 
37 #include "execute_trajectory_service_capability.h"
40 
41 namespace move_group
42 {
43 MoveGroupExecuteService::MoveGroupExecuteService()
44  : MoveGroupCapability("ExecuteTrajectoryService")
45  , callback_queue_()
46  , spinner_(1 /* spinner threads */, &callback_queue_)
47 {
48 }
49 
50 MoveGroupExecuteService::~MoveGroupExecuteService()
51 {
52  spinner_.stop();
53 }
54 
55 void MoveGroupExecuteService::initialize()
56 {
57  // We need to serve each service request in a thread independent of the main spinner thread.
58  // Otherwise, a synchronous execution request (i.e. waiting for the execution to finish) would block
59  // execution of the main spinner thread.
60  // Hence, we use our own asynchronous spinner listening to our own callback queue.
61  ros::AdvertiseServiceOptions ops;
62  ops.template init<moveit_msgs::ExecuteKnownTrajectory>(EXECUTE_SERVICE_NAME, [this](const auto& req, auto& res) {
63  executeTrajectoryService(req, res);
64  });
65  ops.callback_queue = &callback_queue_;
66  execute_service_ = root_node_handle_.advertiseService(ops);
67  spinner_.start();
68 }
69 
70 bool MoveGroupExecuteService::executeTrajectoryService(moveit_msgs::srv::ExecuteKnownTrajectory::Request& req,
71  moveit_msgs::srv::ExecuteKnownTrajectory::Response& res)
72 {
73  ROS_INFO_NAMED(getName(), "Received new trajectory execution service request...");
74  if (!context_->trajectory_execution_manager_)
75  {
76  ROS_ERROR_NAMED(getName(), "Cannot execute trajectory since ~allow_trajectory_execution was set to false");
77  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
78  return true;
79  }
80 
81  // \todo unwind trajectory before execution
82  // robot_trajectory::RobotTrajectory to_exec(planning_scene_monitor_->getRobotModel(), ;
83 
84  context_->trajectory_execution_manager_->clear();
85  if (context_->trajectory_execution_manager_->push(req.trajectory))
86  {
87  context_->trajectory_execution_manager_->execute();
88  if (req.wait_for_execution)
89  {
90  moveit_controller_manager::ExecutionStatus es = context_->trajectory_execution_manager_->waitForExecution();
92  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
94  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
96  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
97  else
98  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
99  ROS_INFO_STREAM_NAMED(getName(), "Execution completed: " << es.asString());
100  }
101  else
102  {
103  ROS_INFO_NAMED(getName(), "Trajectory was successfully forwarded to the controller");
104  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
105  }
106  }
107  else
108  {
109  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
110  }
111  return true;
112 }
113 } // namespace move_group
114 
115 #include <pluginlib/class_list_macros.hpp>
116 
117 PLUGINLIB_EXPORT_CLASS(move_group::MoveGroupExecuteService, move_group::MoveGroupCapability)
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
std::string asString() const
Convert the execution status to a string.