Go to the documentation of this file.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
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";
00046 static const std::string PLANNER_SERVICE_NAME="plan_kinematic_path";
00047 static const std::string ROBOT_DESCRIPTION="robot_description";
00048
00049 class OMPLPlannerService
00050 {
00051 public:
00052
00053 OMPLPlannerService(planning_scene_monitor::PlanningSceneMonitor &psm, bool debug = false) :
00054 nh_("~"), psm_(psm), ompl_interface_(psm.getPlanningScene()->getRobotModel()), debug_(debug)
00055 {
00056 plan_service_ = nh_.advertiseService(PLANNER_SERVICE_NAME, &OMPLPlannerService::computePlan, this);
00057 if (debug_)
00058 {
00059 pub_plan_ = nh_.advertise<moveit_msgs::DisplayTrajectory>("display_motion_plan", 100);
00060 pub_request_ = nh_.advertise<moveit_msgs::MotionPlanRequest>("motion_plan_request", 100);
00061 }
00062 }
00063
00064 bool computePlan(moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res)
00065 {
00066 ROS_INFO("Received new planning request...");
00067 if (debug_)
00068 pub_request_.publish(req.motion_plan_request);
00069 planning_interface::MotionPlanResponse response;
00070
00071 ompl_interface::ModelBasedPlanningContextPtr context =
00072 ompl_interface_.getPlanningContext(psm_.getPlanningScene(), req.motion_plan_request);
00073 if (!context)
00074 {
00075 ROS_ERROR_STREAM_NAMED("computePlan","No planning context found");
00076 return false;
00077 }
00078 context->clear();
00079
00080 bool result = context->solve(response);
00081
00082 if (debug_)
00083 {
00084 if (result)
00085 displaySolution(res.motion_plan_response);
00086 std::stringstream ss;
00087 ROS_INFO("%s", ss.str().c_str());
00088 }
00089 return result;
00090 }
00091
00092 void displaySolution(const moveit_msgs::MotionPlanResponse &mplan_res)
00093 {
00094 moveit_msgs::DisplayTrajectory d;
00095 d.model_id = psm_.getPlanningScene()->getRobotModel()->getName();
00096 d.trajectory_start = mplan_res.trajectory_start;
00097 d.trajectory.resize(1, mplan_res.trajectory);
00098 pub_plan_.publish(d);
00099 }
00100
00101 void status()
00102 {
00103 ompl_interface_.printStatus();
00104 ROS_INFO("Responding to planning and bechmark requests");
00105 if (debug_)
00106 ROS_INFO("Publishing debug information");
00107 }
00108
00109 private:
00110
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 }