00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #include <moveit/planning_pipeline/planning_pipeline.h>
00036 #include <moveit/robot_state/conversions.h>
00037 #include <moveit/collision_detection/collision_tools.h>
00038 #include <moveit/trajectory_processing/trajectory_tools.h>
00039 #include <moveit_msgs/DisplayTrajectory.h>
00040 #include <visualization_msgs/MarkerArray.h>
00041 #include <boost/tokenizer.hpp>
00042 #include <boost/algorithm/string/join.hpp>
00043 #include <sstream>
00044 
00045 const std::string planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC = "display_planned_path";
00046 const std::string planning_pipeline::PlanningPipeline::MOTION_PLAN_REQUEST_TOPIC = "motion_plan_request";
00047 const std::string planning_pipeline::PlanningPipeline::MOTION_CONTACTS_TOPIC = "display_contacts";
00048 
00049 planning_pipeline::PlanningPipeline::PlanningPipeline(const robot_model::RobotModelConstPtr& model,
00050                                                       const ros::NodeHandle &nh,
00051                                                       const std::string &planner_plugin_param_name,
00052                                                       const std::string &adapter_plugins_param_name) :
00053   nh_(nh),
00054   kmodel_(model)
00055 {
00056   std::string planner;
00057   if (nh_.getParam(planner_plugin_param_name, planner))
00058     planner_plugin_name_ = planner;
00059 
00060   std::string adapters;
00061   if (nh_.getParam(adapter_plugins_param_name, adapters))
00062   {
00063     boost::char_separator<char> sep(" ");
00064     boost::tokenizer<boost::char_separator<char> > tok(adapters, sep);
00065     for(boost::tokenizer<boost::char_separator<char> >::iterator beg = tok.begin() ; beg != tok.end(); ++beg)
00066       adapter_plugin_names_.push_back(*beg);
00067   }
00068 
00069   configure();
00070 }
00071 
00072 planning_pipeline::PlanningPipeline::PlanningPipeline(const robot_model::RobotModelConstPtr& model,
00073                                                       const ros::NodeHandle &nh,
00074                                                       const std::string &planner_plugin_name,
00075                                                       const std::vector<std::string> &adapter_plugin_names) :
00076   nh_(nh),
00077   planner_plugin_name_(planner_plugin_name),
00078   adapter_plugin_names_(adapter_plugin_names),
00079   kmodel_(model)
00080 {
00081   configure();
00082 }
00083 
00084 void planning_pipeline::PlanningPipeline::configure()
00085 {
00086   check_solution_paths_ = false;          
00087   publish_received_requests_ = false;
00088   display_computed_motion_plans_ = false; 
00089 
00090   
00091   try
00092   {
00093     planner_plugin_loader_.reset(new pluginlib::ClassLoader<planning_interface::PlannerManager>("moveit_core", "planning_interface::PlannerManager"));
00094   }
00095   catch(pluginlib::PluginlibException& ex)
00096   {
00097     ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what());
00098   }
00099 
00100   std::vector<std::string> classes;
00101   if (planner_plugin_loader_)
00102     classes = planner_plugin_loader_->getDeclaredClasses();
00103   if (planner_plugin_name_.empty() && classes.size() == 1)
00104   {
00105     planner_plugin_name_ = classes[0];
00106     ROS_INFO("No '~planning_plugin' parameter specified, but only '%s' planning plugin is available. Using that one.", planner_plugin_name_.c_str());
00107   }
00108   if (planner_plugin_name_.empty() && classes.size() > 1)
00109   {
00110     planner_plugin_name_ = classes[0];
00111     ROS_INFO("Multiple planning plugins available. You should specify the '~planning_plugin' parameter. Using '%s' for now.", planner_plugin_name_.c_str());
00112   }
00113   try
00114   {
00115     planner_instance_.reset(planner_plugin_loader_->createUnmanagedInstance(planner_plugin_name_));
00116     if (!planner_instance_->initialize(kmodel_, nh_.getNamespace()))
00117       throw std::runtime_error("Unable to initialize planning plugin");
00118     ROS_INFO_STREAM("Using planning interface '" << planner_instance_->getDescription() << "'");
00119   }
00120   catch(pluginlib::PluginlibException& ex)
00121   {
00122     ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name_ << "': " << ex.what() << std::endl
00123                      << "Available plugins: " << boost::algorithm::join(classes, ", "));
00124   }
00125 
00126   
00127   if (!adapter_plugin_names_.empty())
00128   {
00129     std::vector<planning_request_adapter::PlanningRequestAdapterConstPtr> ads;
00130     try
00131     {
00132       adapter_plugin_loader_.reset(new pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>("moveit_core", "planning_request_adapter::PlanningRequestAdapter"));
00133     }
00134     catch(pluginlib::PluginlibException& ex)
00135     {
00136       ROS_ERROR_STREAM("Exception while creating planning plugin loader " << ex.what());
00137     }
00138 
00139     if (adapter_plugin_loader_)
00140       for (std::size_t i = 0 ; i < adapter_plugin_names_.size() ; ++i)
00141       {
00142         planning_request_adapter::PlanningRequestAdapterConstPtr ad;
00143         try
00144         {
00145           ad.reset(adapter_plugin_loader_->createUnmanagedInstance(adapter_plugin_names_[i]));
00146         }
00147         catch (pluginlib::PluginlibException& ex)
00148         {
00149           ROS_ERROR_STREAM("Exception while loading planning adapter plugin '" << adapter_plugin_names_[i] << "': " << ex.what());
00150         }
00151         if (ad)
00152           ads.push_back(ad);
00153       }
00154     if (!ads.empty())
00155     {
00156       adapter_chain_.reset(new planning_request_adapter::PlanningRequestAdapterChain());
00157       for (std::size_t i = 0 ; i < ads.size() ; ++i)
00158       {
00159         ROS_INFO_STREAM("Using planning request adapter '" << ads[i]->getDescription() << "'");
00160         adapter_chain_->addAdapter(ads[i]);
00161       }
00162     }
00163   }
00164   displayComputedMotionPlans(true);
00165   checkSolutionPaths(true);
00166 }
00167 
00168 void planning_pipeline::PlanningPipeline::displayComputedMotionPlans(bool flag)
00169 {
00170   if (display_computed_motion_plans_ && !flag)
00171     display_path_publisher_.shutdown();
00172   else
00173     if (!display_computed_motion_plans_ && flag)
00174       display_path_publisher_ = nh_.advertise<moveit_msgs::DisplayTrajectory>(DISPLAY_PATH_TOPIC, 10, true);
00175   display_computed_motion_plans_ = flag;
00176 }
00177 
00178 void planning_pipeline::PlanningPipeline::publishReceivedRequests(bool flag)
00179 {
00180   if (publish_received_requests_ && !flag)
00181     received_request_publisher_.shutdown();
00182   else
00183     if (!publish_received_requests_ && flag)
00184       received_request_publisher_ = nh_.advertise<moveit_msgs::MotionPlanRequest>(MOTION_PLAN_REQUEST_TOPIC, 10, true);
00185   publish_received_requests_ = flag;
00186 }
00187 
00188 void planning_pipeline::PlanningPipeline::checkSolutionPaths(bool flag)
00189 {
00190   if (check_solution_paths_ && !flag)
00191     contacts_publisher_.shutdown();
00192   else
00193     if (!check_solution_paths_ && flag)
00194       contacts_publisher_ = nh_.advertise<visualization_msgs::MarkerArray>(MOTION_CONTACTS_TOPIC, 100, true);
00195   check_solution_paths_ = flag;
00196 }
00197 
00198 bool planning_pipeline::PlanningPipeline::generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
00199                                                        const planning_interface::MotionPlanRequest& req,
00200                                                        planning_interface::MotionPlanResponse& res) const
00201 {
00202   std::vector<std::size_t> dummy;
00203   return generatePlan(planning_scene, req, res, dummy);
00204 }
00205 
00206 bool planning_pipeline::PlanningPipeline::generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
00207                                                        const planning_interface::MotionPlanRequest& req,
00208                                                        planning_interface::MotionPlanResponse& res,
00209                                                        std::vector<std::size_t> &adapter_added_state_index) const
00210 {
00211   
00212   if (publish_received_requests_)
00213     received_request_publisher_.publish(req);
00214   adapter_added_state_index.clear();
00215 
00216   if (!planner_instance_)
00217   {
00218     ROS_ERROR("No planning plugin loaded. Cannot plan.");
00219     return false;
00220   }
00221 
00222   bool solved = false;
00223   try
00224   {
00225     if (adapter_chain_)
00226     {
00227       solved = adapter_chain_->adaptAndPlan(planner_instance_, planning_scene, req, res, adapter_added_state_index);
00228       if (!adapter_added_state_index.empty())
00229       {
00230         std::stringstream ss;
00231         for (std::size_t i = 0 ; i < adapter_added_state_index.size() ; ++i)
00232           ss << adapter_added_state_index[i] << " ";
00233         ROS_DEBUG("Planning adapters have added states at index positions: [ %s]", ss.str().c_str());
00234       }
00235     }
00236     else
00237     {
00238       planning_interface::PlanningContextPtr context = planner_instance_->getPlanningContext(planning_scene, req, res.error_code_);
00239       solved = context ? context->solve(res) : false;
00240     }
00241   }
00242   catch(std::runtime_error &ex)
00243   {
00244     ROS_ERROR("Exception caught: '%s'", ex.what());
00245     return false;
00246   }
00247   catch(...)
00248   {
00249     ROS_ERROR("Unknown exception thrown by planner");
00250     return false;
00251   }
00252   bool valid = true;
00253 
00254   if (solved && res.trajectory_)
00255   {
00256     std::size_t state_count = res.trajectory_->getWayPointCount();
00257     ROS_DEBUG_STREAM("Motion planner reported a solution path with " << state_count << " states");
00258     if (check_solution_paths_)
00259     {
00260       std::vector<std::size_t> index;
00261       if (!planning_scene->isPathValid(*res.trajectory_, req.path_constraints, req.group_name, false, &index))
00262       {
00263         
00264         
00265         bool problem = false;
00266         for (std::size_t i = 0 ; i < index.size() && !problem ; ++i)
00267         {
00268           bool found = false;
00269           for (std::size_t j = 0 ; j < adapter_added_state_index.size() ; ++j)
00270             if (index[i] == adapter_added_state_index[j])
00271             {
00272               found = true;
00273               break;
00274             }
00275           if (!found)
00276             problem = true;
00277         }
00278         if (problem)
00279         {
00280           if (index.size() == 1 && index[0] == 0) 
00281             ROS_DEBUG("It appears the robot is starting at an invalid state, but that is ok.");
00282           else
00283           {
00284             valid = false;
00285             res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
00286 
00287             
00288             std::stringstream ss;
00289             for (std::size_t i = 0 ; i < index.size() ; ++i)
00290               ss << index[i] << " ";
00291             ROS_ERROR_STREAM("Computed path is not valid. Invalid states at index locations: [ " << ss.str() << "] out of " << state_count);
00292 
00293             
00294             visualization_msgs::MarkerArray arr;
00295             for (std::size_t i = 0 ; i < index.size() ; ++i)
00296             {
00297               
00298               const robot_state::RobotState &kstate = res.trajectory_->getWayPoint(index[i]);
00299               planning_scene->isStateValid(kstate, req.group_name, true);
00300 
00301               
00302               collision_detection::CollisionRequest c_req;
00303               collision_detection::CollisionResult c_res;
00304               c_req.contacts = true;
00305               c_req.max_contacts = 10;
00306               c_req.max_contacts_per_pair = 3;
00307               c_req.verbose = false;
00308               planning_scene->checkCollision(c_req, c_res, kstate);
00309               if (c_res.contact_count > 0)
00310               {
00311                 visualization_msgs::MarkerArray arr_i;
00312                 collision_detection::getCollisionMarkersFromContacts(arr_i, planning_scene->getPlanningFrame(), c_res.contacts);
00313                 arr.markers.insert(arr.markers.end(), arr_i.markers.begin(), arr_i.markers.end());
00314               }
00315             }
00316             if (!arr.markers.empty())
00317               contacts_publisher_.publish(arr);
00318           }
00319         }
00320         else
00321           ROS_DEBUG("Planned path was found to be valid, except for states that were added by planning request adapters, but that is ok.");
00322       }
00323       else
00324         ROS_DEBUG("Planned path was found to be valid when rechecked");
00325     }
00326   }
00327 
00328   
00329   if (display_computed_motion_plans_ && solved)
00330   {
00331     moveit_msgs::DisplayTrajectory disp;
00332     disp.model_id = kmodel_->getName();
00333     disp.trajectory.resize(1);
00334     res.trajectory_->getRobotTrajectoryMsg(disp.trajectory[0]);
00335     robot_state::robotStateToRobotStateMsg(res.trajectory_->getFirstWayPoint(), disp.trajectory_start);
00336     display_path_publisher_.publish(disp);
00337   }
00338 
00339   return solved && valid;
00340 }
00341 
00342 void planning_pipeline::PlanningPipeline::terminate() const
00343 {
00344   if (planner_instance_)
00345     planner_instance_->terminate();
00346 }