38 #include <boost/bind.hpp> 54 return context->solve(res);
61 const planning_scene::PlanningSceneConstPtr& planning_scene,
64 std::vector<std::size_t>& added_path_index)
const 66 return adaptAndPlan(boost::bind(&callPlannerInterfaceSolve, planner.get(), _1, _2, _3), planning_scene, req, res,
71 const planning_scene::PlanningSceneConstPtr& planning_scene,
75 std::vector<std::size_t> dummy;
76 return adaptAndPlan(planner, planning_scene, req, res, dummy);
83 bool callAdapter1(
const PlanningRequestAdapter* adapter,
const planning_interface::PlannerManagerPtr& planner,
84 const planning_scene::PlanningSceneConstPtr& planning_scene,
86 std::vector<std::size_t>& added_path_index)
90 return adapter->
adaptAndPlan(planner, planning_scene, req, res, added_path_index);
92 catch (std::exception& ex)
94 ROS_ERROR_NAMED(
"planning_request_adapter",
"Exception caught executing *final* adapter '%s': %s",
96 added_path_index.clear();
97 return callPlannerInterfaceSolve(planner.get(), planning_scene, req, res);
102 const planning_scene::PlanningSceneConstPtr& planning_scene,
104 std::vector<std::size_t>& added_path_index)
108 return adapter->
adaptAndPlan(planner, planning_scene, req, res, added_path_index);
110 catch (std::exception& ex)
112 ROS_ERROR_NAMED(
"planning_request_adapter",
"Exception caught executing *next* adapter '%s': %s",
114 added_path_index.clear();
115 return planner(planning_scene, req, res);
121 const planning_scene::PlanningSceneConstPtr& planning_scene,
125 std::vector<std::size_t> dummy;
126 return adaptAndPlan(planner, planning_scene, req, res, dummy);
130 const planning_scene::PlanningSceneConstPtr& planning_scene,
133 std::vector<std::size_t>& added_path_index)
const 136 if (adapters_.empty())
138 added_path_index.clear();
139 return callPlannerInterfaceSolve(planner.get(), planning_scene, req, res);
144 std::vector<std::vector<std::size_t> > added_path_index_each(adapters_.size());
149 boost::ref(added_path_index_each.back()));
150 for (
int i = adapters_.size() - 2; i >= 0; --i)
151 fn = boost::bind(&callAdapter2, adapters_[i].
get(), fn, _1, _2, _3, boost::ref(added_path_index_each[i]));
152 bool result = fn(planning_scene, req, res);
153 added_path_index.clear();
156 for (std::size_t i = 0; i < added_path_index_each.size(); ++i)
157 for (std::size_t j = 0; j < added_path_index_each[i].size(); ++j)
159 for (std::size_t k = 0; k < added_path_index.size(); ++k)
160 if (added_path_index_each[i][j] <= added_path_index[k])
161 added_path_index[k]++;
162 added_path_index.push_back(added_path_index_each[i][j]);
164 std::sort(added_path_index.begin(), added_path_index.end());
virtual std::string getDescription() const
Get a short string that identifies the planning request adapter.
moveit_msgs::MoveItErrorCodes error_code_
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...
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
This namespace includes the central class for representing planning contexts.
moveit_msgs::MotionPlanRequest MotionPlanRequest
boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
Generic interface to adapting motion planning requests.
#define ROS_ERROR_NAMED(name,...)
Base class for a MoveIt! planner.
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const