ompl_planner.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2011, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan, Sachin Chitta */
00036 
00037 #include <moveit/ompl_interface/ompl_interface.h>
00038 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00039 #include <tf/transform_listener.h>
00040 #include <moveit_msgs/DisplayTrajectory.h>
00041 #include <moveit/profiler/profiler.h>
00042 #include <moveit_msgs/GetMotionPlan.h>
00043 
00044 static const std::string PLANNER_NODE_NAME="ompl_planning";          // name of node
00045 static const std::string PLANNER_SERVICE_NAME="plan_kinematic_path"; // name of the advertised service (within the ~ namespace)
00046 static const std::string ROBOT_DESCRIPTION="robot_description";      // name of the robot description (a param name, so it can be changed externally)
00047 
00048 class OMPLPlannerService
00049 {
00050 public:
00051 
00052   OMPLPlannerService(planning_scene_monitor::PlanningSceneMonitor &psm, bool debug = false) :
00053     nh_("~"), psm_(psm), ompl_interface_(psm.getPlanningScene()->getRobotModel()), debug_(debug)
00054   {
00055     plan_service_ = nh_.advertiseService(PLANNER_SERVICE_NAME, &OMPLPlannerService::computePlan, this);
00056     if (debug_)
00057     {
00058       pub_plan_ = nh_.advertise<moveit_msgs::DisplayTrajectory>("display_motion_plan", 100);
00059       pub_request_ = nh_.advertise<moveit_msgs::MotionPlanRequest>("motion_plan_request", 100);
00060     }
00061   }
00062 
00063   bool computePlan(moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res)
00064   {
00065     ROS_INFO("Received new planning request...");
00066     if (debug_)
00067       pub_request_.publish(req.motion_plan_request);
00068     planning_interface::MotionPlanResponse response;
00069     bool result = ompl_interface_.solve(psm_.getPlanningScene(), req.motion_plan_request, response);
00070     res.motion_plan_response.error_code = response.error_code_;
00071 
00072     if (debug_)
00073     {
00074       if (result)
00075         displaySolution(res.motion_plan_response);
00076       std::stringstream ss;
00077       ROS_INFO("%s", ss.str().c_str());
00078     }
00079     return result;
00080   }
00081 
00082   void displaySolution(const moveit_msgs::MotionPlanResponse &mplan_res)
00083   {
00084     moveit_msgs::DisplayTrajectory d;
00085     d.model_id = psm_.getPlanningScene()->getRobotModel()->getName();
00086     d.trajectory_start = mplan_res.trajectory_start;
00087     d.trajectory.resize(1, mplan_res.trajectory);
00088     pub_plan_.publish(d);
00089   }
00090 
00091   void status()
00092   {
00093     ompl_interface_.printStatus();
00094     ROS_INFO("Responding to planning and bechmark requests");
00095     if (debug_)
00096       ROS_INFO("Publishing debug information");
00097   }
00098 
00099 private:
00100 
00101   ros::NodeHandle                               nh_;
00102   planning_scene_monitor::PlanningSceneMonitor &psm_;
00103   ompl_interface::OMPLInterface                 ompl_interface_;
00104   ros::ServiceServer                            plan_service_;
00105   ros::ServiceServer                            display_states_service_;
00106   ros::Publisher                                pub_plan_;
00107   ros::Publisher                                pub_request_;
00108   bool                                          debug_;
00109 };
00110 
00111 int main(int argc, char **argv)
00112 {
00113   ros::init(argc, argv, PLANNER_NODE_NAME);
00114 
00115   bool debug = false;
00116   for (int i = 1 ; i < argc ; ++i)
00117     if (strncmp(argv[i], "--debug", 7) == 0)
00118       debug = true;
00119 
00120   ros::AsyncSpinner spinner(1);
00121   spinner.start();
00122 
00123   boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener());
00124   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION, tf);
00125   if (psm.getPlanningScene())
00126   {
00127     psm.startWorldGeometryMonitor();
00128     psm.startSceneMonitor();
00129     psm.startStateMonitor();
00130 
00131     OMPLPlannerService pservice(psm, debug);
00132     pservice.status();
00133     ros::waitForShutdown();
00134   }
00135   else
00136     ROS_ERROR("Planning scene not configured");
00137 
00138   return 0;
00139 }


ompl
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:12:03