39 #include <moveit_msgs/GetMotionPlan.h> 42 #include <boost/shared_ptr.hpp> 55 bool initialize(
const robot_model::RobotModelConstPtr& model,
const std::string& ns)
57 for (
const std::string& group : model->getJointModelGroupNames())
67 moveit_msgs::MoveItErrorCodes& error_code)
const 69 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
71 if (req.group_name.empty())
73 ROS_ERROR(
"No group specified to plan for");
74 error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
75 return planning_interface::PlanningContextPtr();
80 ROS_ERROR(
"No planning scene supplied as input");
81 error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
82 return planning_interface::PlanningContextPtr();
86 planning_scene::PlanningScenePtr ps = planning_scene->diff();
91 context->setPlanningScene(ps);
92 context->setMotionPlanRequest(req);
93 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
static CollisionDetectorAllocatorPtr create()
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::string getDescription() const
std::map< std::string, CHOMPPlanningContextPtr > planning_contexts_