chomp_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 
39 #include <moveit_msgs/GetMotionPlan.h>
41 
42 #include <boost/shared_ptr.hpp>
43 
45 
46 namespace chomp_interface
47 {
49 {
50 public:
52  {
53  }
54 
55  bool initialize(const robot_model::RobotModelConstPtr& model, const std::string& ns)
56  {
57  for (const std::string& group : model->getJointModelGroupNames())
58  {
59  planning_contexts_[group] =
60  CHOMPPlanningContextPtr(new CHOMPPlanningContext("chomp_planning_context", group, model));
61  }
62  return true;
63  }
64 
65  planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
67  moveit_msgs::MoveItErrorCodes& error_code) const
68  {
69  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
70 
71  if (req.group_name.empty())
72  {
73  ROS_ERROR("No group specified to plan for");
74  error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
75  return planning_interface::PlanningContextPtr();
76  }
77 
78  if (!planning_scene)
79  {
80  ROS_ERROR("No planning scene supplied as input");
81  error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
82  return planning_interface::PlanningContextPtr();
83  }
84 
85  // create PlanningScene using hybrid collision detector
86  planning_scene::PlanningScenePtr ps = planning_scene->diff();
87  ps->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorHybrid::create(), true);
88 
89  // retrieve and configure existing context
90  const CHOMPPlanningContextPtr& context = planning_contexts_.at(req.group_name);
91  context->setPlanningScene(ps);
92  context->setMotionPlanRequest(req);
93  error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
94  return context;
95  }
96 
98  {
99  // TODO: this is a dummy implementation
100  // capabilities.dummy = false;
101  return true;
102  }
103 
104  std::string getDescription() const
105  {
106  return "CHOMP";
107  }
108 
109  void getPlanningAlgorithms(std::vector<std::string>& algs) const
110  {
111  algs.resize(1);
112  algs[0] = "CHOMP";
113  }
114 
115 protected:
116  std::map<std::string, CHOMPPlanningContextPtr> planning_contexts_;
117 };
118 
119 } // ompl_interface_ros
120 
bool initialize(const robot_model::RobotModelConstPtr &model, const std::string &ns)
PLUGINLIB_EXPORT_CLASS(chomp_interface::CHOMPPlannerManager, planning_interface::PlannerManager)
bool canServiceRequest(const planning_interface::MotionPlanRequest &req) const
moveit_msgs::MotionPlanRequest MotionPlanRequest
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const
void getPlanningAlgorithms(std::vector< std::string > &algs) const
std::map< std::string, CHOMPPlanningContextPtr > planning_contexts_
#define ROS_ERROR(...)


chomp_interface
Author(s): Gil Jones
autogenerated on Wed Jul 10 2019 04:04:17