moveit2
The MoveIt Motion Planning Framework for ROS 2.
plan_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 
38 
42 
43 namespace move_group
44 {
45 static const rclcpp::Logger LOGGER =
46  rclcpp::get_logger("moveit_move_group_default_capabilities.plan_service_capability");
47 
49 {
50 }
51 
53 {
54  plan_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetMotionPlan>(
55  PLANNER_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& request_header,
56  const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Request>& req,
57  const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Response>& res) {
58  return computePlanService(request_header, req, res);
59  });
60 }
61 
62 bool MoveGroupPlanService::computePlanService(const std::shared_ptr<rmw_request_id_t>& /* unused */,
63  const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Request>& req,
64  const std::shared_ptr<moveit_msgs::srv::GetMotionPlan::Response>& res)
65 {
66  RCLCPP_INFO(LOGGER, "Received new planning service request...");
67  // before we start planning, ensure that we have the latest robot state received...
68  if (static_cast<bool>(req->motion_plan_request.start_state.is_diff))
69  context_->planning_scene_monitor_->waitForCurrentRobotState(context_->moveit_cpp_->getNode()->get_clock()->now());
70  context_->planning_scene_monitor_->updateFrameTransforms();
71 
72  // Select planning_pipeline to handle request
73  const planning_pipeline::PlanningPipelinePtr planning_pipeline =
74  resolvePlanningPipeline(req->motion_plan_request.pipeline_id);
75  if (!planning_pipeline)
76  {
77  res->motion_plan_response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
78  return true;
79  }
80 
81  planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);
82  try
83  {
85  planning_pipeline->generatePlan(ps, req->motion_plan_request, mp_res);
86  mp_res.getMessage(res->motion_plan_response);
87  }
88  catch (std::exception& ex)
89  {
90  RCLCPP_ERROR(LOGGER, "Planning pipeline threw an exception: %s", ex.what());
91  res->motion_plan_response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
92  }
93 
94  return true;
95 }
96 } // namespace move_group
97 
98 #include <pluginlib/class_list_macros.hpp>
99 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Planning pipeline.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const