planning_request_adapter.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 
39 #include <functional>
40 #include <algorithm>
41 
43 {
44 namespace
45 {
46 bool callPlannerInterfaceSolve(const planning_interface::PlannerManager& planner,
47  const planning_scene::PlanningSceneConstPtr& planning_scene,
50 {
51  planning_interface::PlanningContextPtr context = planner.getPlanningContext(planning_scene, req, res.error_code_);
52  if (context)
53  return context->solve(res);
54  else
55  return false;
56 }
57 
58 bool callAdapter(const PlanningRequestAdapter& adapter, const PlanningRequestAdapter::PlannerFn& planner,
59  const planning_scene::PlanningSceneConstPtr& planning_scene,
61  std::vector<std::size_t>& added_path_index)
62 {
63  try
64  {
65  bool result = adapter.adaptAndPlan(planner, planning_scene, req, res, added_path_index);
66  ROS_DEBUG_STREAM_NAMED("planning_request_adapter", adapter.getDescription()
68  return result;
69  }
70  catch (std::exception& ex)
71  {
72  ROS_ERROR_NAMED("planning_request_adapter",
73  "Exception caught executing adapter '%s': %s\nSkipping adapter instead.",
74  adapter.getDescription().c_str(), ex.what());
75  added_path_index.clear();
76  return planner(planning_scene, req, res);
77  }
78 }
79 
80 } // namespace
81 
82 bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
83  const planning_scene::PlanningSceneConstPtr& planning_scene,
86  std::vector<std::size_t>& added_path_index) const
87 {
88  return adaptAndPlan(
89  [&planner](const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
91  return callPlannerInterfaceSolve(*planner, scene, req, res);
92  },
93  planning_scene, req, res, added_path_index);
94 }
95 
96 bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
97  const planning_scene::PlanningSceneConstPtr& planning_scene,
100 {
101  std::vector<std::size_t> dummy;
102  return adaptAndPlan(planner, planning_scene, req, res, dummy);
103 }
104 
105 bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
106  const planning_scene::PlanningSceneConstPtr& planning_scene,
109 {
110  std::vector<std::size_t> dummy;
111  return adaptAndPlan(planner, planning_scene, req, res, dummy);
112 }
113 
114 bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
115  const planning_scene::PlanningSceneConstPtr& planning_scene,
118  std::vector<std::size_t>& added_path_index) const
119 {
120  // if there are no adapters, run the planner directly
121  if (adapters_.empty())
122  {
123  added_path_index.clear();
124  return callPlannerInterfaceSolve(*planner, planning_scene, req, res);
125  }
126  else
127  {
128  // the index values added by each adapter
129  std::vector<std::vector<std::size_t> > added_path_index_each(adapters_.size());
130 
131  // if there are adapters, construct a function for each, in order,
132  // so that in the end we have a nested sequence of functions that calls all adapters
133  // and eventually the planner in the correct order.
134  PlanningRequestAdapter::PlannerFn fn = [&planner = *planner](const planning_scene::PlanningSceneConstPtr& scene,
137  return callPlannerInterfaceSolve(planner, scene, req, res);
138  };
139 
140  for (int i = adapters_.size() - 1; i >= 0; --i)
141  {
142  fn = [&adapter = *adapters_[i], fn, &added_path_index = added_path_index_each[i]](
143  const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
145  return callAdapter(adapter, fn, scene, req, res, added_path_index);
146  };
147  }
148 
149  bool result = fn(planning_scene, req, res);
150  added_path_index.clear();
151 
152  // merge the index values from each adapter (in reverse order)
153  for (auto added_state_by_each_adapter_it = added_path_index_each.rbegin();
154  added_state_by_each_adapter_it != added_path_index_each.rend(); ++added_state_by_each_adapter_it)
155  for (std::size_t added_index : *added_state_by_each_adapter_it)
156  {
157  for (std::size_t& index_in_path : added_path_index)
158  if (added_index <= index_in_path)
159  index_in_path++;
160  added_path_index.push_back(added_index);
161  }
162  std::sort(added_path_index.begin(), added_path_index.end());
163  return result;
164  }
165 }
166 
167 } // end of namespace planning_request_adapter
planning_interface::PlannerManager::getPlanningContext
virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const =0
Construct a planning context given the current scene and a planning request. If a problem is encounte...
planning_request_adapter::PlanningRequestAdapterChain::adaptAndPlan
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
Definition: planning_request_adapter.cpp:137
planning_interface::MotionPlanResponse
Definition: planning_response.h:78
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
Definition: planning_response.h:114
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
planning_request_adapter.h
moveit::core::MoveItErrorCode
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Definition: moveit_error_code.h:110
planning_request_adapter::PlanningRequestAdapter::adaptAndPlan
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
Definition: planning_request_adapter.cpp:128
moveit_error_code.h
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
Definition: planning_request.h:77
planning_request_adapter::PlanningRequestAdapterChain::adapters_
std::vector< PlanningRequestAdapterConstPtr > adapters_
Definition: planning_request_adapter.h:151
planning_request_adapter::PlanningRequestAdapter::PlannerFn
boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Definition: planning_request_adapter.h:86
planning_request_adapter
Generic interface to adapting motion planning requests.
Definition: planning_request_adapter.h:45
planning_scene
This namespace includes the central class for representing planning scenes.
Definition: planning_interface.h:45
planning_interface::PlannerManager
Base class for a MoveIt planner.
Definition: planning_interface.h:150


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Tue Dec 24 2024 03:27:14