moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group_sequence_service.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 // Modified by Pilz GmbH & Co. KG
38 
40 
44 
46 #include <moveit/utils/logger.hpp>
47 
49 {
50 namespace
51 {
52 rclcpp::Logger getLogger()
53 {
54  return moveit::getLogger("pilz_move_group_sequence_service");
55 }
56 } // namespace
57 MoveGroupSequenceService::MoveGroupSequenceService() : MoveGroupCapability("SequenceService")
58 {
59 }
60 
62 {
63 }
64 
66 {
67  command_list_manager_ = std::make_unique<pilz_industrial_motion_planner::CommandListManager>(
68  context_->moveit_cpp_->getNode(), context_->planning_scene_monitor_->getRobotModel());
69 
70  sequence_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetMotionSequence>(
71  SEQUENCE_SERVICE_NAME,
72  [this](const moveit_msgs::srv::GetMotionSequence::Request::SharedPtr& req,
73  const moveit_msgs::srv::GetMotionSequence::Response::SharedPtr& res) { return plan(req, res); });
74 }
75 
76 bool MoveGroupSequenceService::plan(const moveit_msgs::srv::GetMotionSequence::Request::SharedPtr& req,
77  const moveit_msgs::srv::GetMotionSequence::Response::SharedPtr& res)
78 {
79  // Handle empty requests
80  if (req->request.items.empty())
81  {
82  RCLCPP_WARN(getLogger(), "Received empty request. That's ok but maybe not what you intended.");
83  res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
84  return true;
85  }
86 
87  // TODO: Do we lock on the correct scene? Does the lock belong to the scene
88  // used for planning?
89  planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);
90 
91  rclcpp::Time planning_start = context_->moveit_cpp_->getNode()->now();
92  RobotTrajCont traj_vec;
93  try
94  {
95  // Select planning_pipeline to handle request
96  // All motions in the SequenceRequest need to use the same planning pipeline (but can use different planners)
97  const planning_pipeline::PlanningPipelinePtr planning_pipeline =
98  resolvePlanningPipeline(req->request.items[0].req.pipeline_id);
99  if (!planning_pipeline)
100  {
101  RCLCPP_ERROR_STREAM(getLogger(), "Could not load planning pipeline " << req->request.items[0].req.pipeline_id);
102  res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
103  return false;
104  }
105 
106  traj_vec = command_list_manager_->solve(ps, context_->planning_pipeline_, req->request);
107  }
108  catch (const MoveItErrorCodeException& ex)
109  {
110  RCLCPP_ERROR_STREAM(getLogger(),
111  "Planner threw an exception (error code: " << ex.getErrorCode() << "): " << ex.what());
112  res->response.error_code.val = ex.getErrorCode();
113  return true;
114  }
115  // LCOV_EXCL_START // Keep moveit up even if lower parts throw
116  catch (const std::exception& ex)
117  {
118  RCLCPP_ERROR_STREAM(getLogger(), "Planner threw an exception: " << ex.what());
119  // If 'FALSE' then no response will be sent to the caller.
120  return false;
121  }
122  // LCOV_EXCL_STOP
123 
124  res->response.planned_trajectories.resize(traj_vec.size());
125  for (RobotTrajCont::size_type i = 0; i < traj_vec.size(); ++i)
126  {
127  move_group::MoveGroupCapability::convertToMsg(traj_vec.at(i), res->response.sequence_start,
128  res->response.planned_trajectories.at(i));
129  }
130  res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
131  res->response.planning_time = (context_->moveit_cpp_->getNode()->now() - planning_start).seconds();
132  return true;
133 }
134 
135 } // namespace pilz_industrial_motion_planner
136 
137 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
void convertToMsg(const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::msg::RobotState &first_state_msg, std::vector< moveit_msgs::msg::RobotTrajectory > &trajectory_msg) const
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
Provide service to blend multiple trajectories in the form of a MoveGroup capability (plugin).
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont