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 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 */
00036 
00037 #include <moveit/ompl_interface/ompl_interface.h>
00038 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00039 #include <moveit/ompl_interface/model_based_planning_context.h>
00040 #include <tf/transform_listener.h>
00041 #include <moveit_msgs/DisplayTrajectory.h>
00042 #include <moveit/profiler/profiler.h>
00043 #include <moveit_msgs/GetMotionPlan.h>
00044 
00045 static const std::string PLANNER_NODE_NAME = "ompl_planning";  // name of node
00046 static const std::string PLANNER_SERVICE_NAME =
00047     "plan_kinematic_path";  // name of the advertised service (within the ~ namespace)
00048 static const std::string ROBOT_DESCRIPTION =
00049     "robot_description";  // name of the robot description (a param name, so it can be changed externally)
00050 
00051 class OMPLPlannerService
00052 {
00053 public:
00054   OMPLPlannerService(planning_scene_monitor::PlanningSceneMonitor& psm, bool debug = false)
00055     : nh_("~"), psm_(psm), ompl_interface_(psm.getPlanningScene()->getRobotModel()), debug_(debug)
00056   {
00057     plan_service_ = nh_.advertiseService(PLANNER_SERVICE_NAME, &OMPLPlannerService::computePlan, this);
00058     if (debug_)
00059     {
00060       pub_plan_ = nh_.advertise<moveit_msgs::DisplayTrajectory>("display_motion_plan", 100);
00061       pub_request_ = nh_.advertise<moveit_msgs::MotionPlanRequest>("motion_plan_request", 100);
00062     }
00063   }
00064 
00065   bool computePlan(moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res)
00066   {
00067     ROS_INFO("Received new planning request...");
00068     if (debug_)
00069       pub_request_.publish(req.motion_plan_request);
00070     planning_interface::MotionPlanResponse response;
00071 
00072     ompl_interface::ModelBasedPlanningContextPtr context =
00073         ompl_interface_.getPlanningContext(psm_.getPlanningScene(), req.motion_plan_request);
00074     if (!context)
00075     {
00076       ROS_ERROR_STREAM_NAMED("computePlan", "No planning context found");
00077       return false;
00078     }
00079     context->clear();
00080 
00081     bool result = context->solve(response);
00082 
00083     if (debug_)
00084     {
00085       if (result)
00086         displaySolution(res.motion_plan_response);
00087       std::stringstream ss;
00088       ROS_INFO("%s", ss.str().c_str());
00089     }
00090     return result;
00091   }
00092 
00093   void displaySolution(const moveit_msgs::MotionPlanResponse& mplan_res)
00094   {
00095     moveit_msgs::DisplayTrajectory d;
00096     d.model_id = psm_.getPlanningScene()->getRobotModel()->getName();
00097     d.trajectory_start = mplan_res.trajectory_start;
00098     d.trajectory.resize(1, mplan_res.trajectory);
00099     pub_plan_.publish(d);
00100   }
00101 
00102   void status()
00103   {
00104     ompl_interface_.printStatus();
00105     ROS_INFO("Responding to planning and bechmark requests");
00106     if (debug_)
00107       ROS_INFO("Publishing debug information");
00108   }
00109 
00110 private:
00111   ros::NodeHandle nh_;
00112   planning_scene_monitor::PlanningSceneMonitor& psm_;
00113   ompl_interface::OMPLInterface ompl_interface_;
00114   ros::ServiceServer plan_service_;
00115   ros::ServiceServer display_states_service_;
00116   ros::Publisher pub_plan_;
00117   ros::Publisher pub_request_;
00118   bool debug_;
00119 };
00120 
00121 int main(int argc, char** argv)
00122 {
00123   ros::init(argc, argv, PLANNER_NODE_NAME);
00124 
00125   bool debug = false;
00126   for (int i = 1; i < argc; ++i)
00127     if (strncmp(argv[i], "--debug", 7) == 0)
00128       debug = true;
00129 
00130   ros::AsyncSpinner spinner(1);
00131   spinner.start();
00132 
00133   boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener());
00134   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION, tf);
00135   if (psm.getPlanningScene())
00136   {
00137     psm.startWorldGeometryMonitor();
00138     psm.startSceneMonitor();
00139     psm.startStateMonitor();
00140 
00141     OMPLPlannerService pservice(psm, debug);
00142     pservice.status();
00143     ros::waitForShutdown();
00144   }
00145   else
00146     ROS_ERROR("Planning scene not configured");
00147 
00148   return 0;
00149 }


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:27