stomp_planner_manager.cpp
Go to the documentation of this file.
00001 
00026 #include <class_loader/class_loader.h>
00027 #include <stomp_moveit/stomp_planner_manager.h>
00028 #include <stomp_moveit/stomp_planner.h>
00029 
00030 namespace stomp_moveit
00031 {
00032 
00033 StompPlannerManager::StompPlannerManager():
00034     planning_interface::PlannerManager(),
00035     nh_("~")
00036 {
00037 
00038 }
00039 
00040 StompPlannerManager::~StompPlannerManager()
00041 {
00042 
00043 }
00044 
00045 bool StompPlannerManager::initialize(const robot_model::RobotModelConstPtr &model, const std::string &ns)
00046 {
00047   if (!ns.empty())
00048   {
00049     nh_ = ros::NodeHandle(ns);
00050   }
00051 
00052   robot_model_ = model;
00053 
00054   // each element under 'stomp' should be a group name
00055   std::map<std::string, XmlRpc::XmlRpcValue> group_config;
00056 
00057   if (!StompPlanner::getConfigData(nh_, group_config))
00058   {
00059     return false;
00060   }
00061 
00062   for(std::map<std::string, XmlRpc::XmlRpcValue>::iterator v = group_config.begin(); v != group_config.end(); v++)
00063   {
00064     if(!model->hasJointModelGroup(v->first))
00065     {
00066       ROS_WARN("The robot model does not support the planning group '%s' in the STOMP configuration, skipping STOMP setup for this group",
00067                 v->first.c_str());
00068       continue;
00069     }
00070 
00071     boost::shared_ptr<StompPlanner> planner(new StompPlanner(v->first, v->second, robot_model_));
00072     planners_.insert(std::make_pair(v->first, planner));
00073   }
00074 
00075   if(planners_.empty())
00076   {
00077     ROS_ERROR("All planning groups are invalid, STOMP could not be configured");
00078     return false;
00079   }
00080 
00081   return true;
00082 }
00083 
00084 bool StompPlannerManager::canServiceRequest(const moveit_msgs::MotionPlanRequest &req) const
00085 {
00086   if(planners_.count(req.group_name) == 0)
00087   {
00088     return false;
00089   }
00090 
00091   // Get planner
00092   boost::shared_ptr<StompPlanner> planner = boost::static_pointer_cast<StompPlanner>(planners_.at(req.group_name));
00093   return planner->canServiceRequest(req);
00094 }
00095 
00096 void StompPlannerManager::getPlanningAlgorithms(std::vector<std::string> &algs) const
00097 {
00098   algs.clear();
00099   if(!planners_.empty())
00100   {
00101     algs.push_back(planners_.begin()->second->getName());
00102   }
00103 }
00104 
00105 void StompPlannerManager::setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs)
00106 {
00107   ROS_WARN_STREAM("The "<<__FUNCTION__<<" method is not applicable");
00108 }
00109 
00110 planning_interface::PlanningContextPtr StompPlannerManager::getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene,
00111                                                                                const planning_interface::MotionPlanRequest &req,
00112                                                                                moveit_msgs::MoveItErrorCodes &error_code) const
00113 {
00114   error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00115 
00116   if (req.group_name.empty())
00117   {
00118     ROS_ERROR("No group specified to plan for");
00119     error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00120     return planning_interface::PlanningContextPtr();
00121   }
00122 
00123   if (!planning_scene)
00124   {
00125     ROS_ERROR("No planning scene supplied as input");
00126     error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00127     return planning_interface::PlanningContextPtr();
00128   }
00129 
00130   if(planners_.count(req.group_name) <=0)
00131   {
00132     ROS_ERROR("STOMP does not have a planning context for group %s",req.group_name.c_str());
00133     error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00134     return planning_interface::PlanningContextPtr();
00135   }
00136 
00137   // Get planner
00138   boost::shared_ptr<StompPlanner> planner = boost::static_pointer_cast<StompPlanner>(planners_.at(req.group_name));
00139 
00140   if(!planner->canServiceRequest(req))
00141   {
00142     error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00143     return planning_interface::PlanningContextPtr();
00144   }
00145 
00146   // Setup Planner
00147   planner->clear();
00148   planner->setPlanningScene(planning_scene);
00149   planner->setMotionPlanRequest(req);
00150 
00151   // Return Planner
00152   return planner;
00153 }
00154 
00155 
00156 } /* namespace stomp_moveit_interface */
00157 CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompPlannerManager, planning_interface::PlannerManager)


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01