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 <planning_scene_monitor/planning_scene_monitor.h>
00038 #include <ompl_interface_ros/ompl_interface_ros.h>
00039 #include <moveit_msgs/ComputePlanningBenchmark.h>
00040 #include <kinematic_constraints/utils.h>
00041
00042 static const std::string PLANNER_SERVICE_NAME="/ompl_planning/benchmark_planning_problem";
00043 static const std::string ROBOT_DESCRIPTION="robot_description";
00044
00045 void benchmarkSimplePlan(const std::string &config)
00046 {
00047 ros::NodeHandle nh;
00048 ros::service::waitForService(PLANNER_SERVICE_NAME);
00049 ros::ServiceClient benchmark_service_client = nh.serviceClient<moveit_msgs::ComputePlanningBenchmark>(PLANNER_SERVICE_NAME);
00050
00051 moveit_msgs::ComputePlanningBenchmark::Request mplan_req;
00052 moveit_msgs::ComputePlanningBenchmark::Response mplan_res;
00053
00054 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00055 planning_scene::PlanningScene &scene = *psm.getPlanningScene();
00056
00057 mplan_req.motion_plan_request.num_planning_attempts = 50;
00058 mplan_req.motion_plan_request.planner_id = config;
00059 mplan_req.motion_plan_request.group_name = "right_arm";
00060 mplan_req.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00061 const std::vector<std::string>& joint_names = scene.getRobotModel()->getJointModelGroup("right_arm")->getJointModelNames();
00062 mplan_req.motion_plan_request.goal_constraints.resize(1);
00063 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints.resize(joint_names.size());
00064 for(unsigned int i = 0; i < joint_names.size(); i++)
00065 {
00066 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].joint_name = joint_names[i];
00067 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].position = 0.0;
00068 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_above = 0.001;
00069 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_below = 0.001;
00070 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].weight = 1.0;
00071 }
00072 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[0].position = -2.0;
00073 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[3].position = -.2;
00074 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[5].position = -.2;
00075
00076 benchmark_service_client.call(mplan_req, mplan_res);
00077 }
00078
00079 void benchmarkPathConstrained(const std::string &config)
00080 {
00081 ros::NodeHandle nh;
00082 ros::service::waitForService(PLANNER_SERVICE_NAME);
00083 ros::ServiceClient benchmark_service_client = nh.serviceClient<moveit_msgs::ComputePlanningBenchmark>(PLANNER_SERVICE_NAME);
00084
00085 moveit_msgs::ComputePlanningBenchmark::Request mplan_req;
00086 moveit_msgs::ComputePlanningBenchmark::Response mplan_res;
00087
00088 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00089 planning_scene::PlanningScene &scene = *psm.getPlanningScene();
00090
00091 mplan_req.motion_plan_request.num_planning_attempts = 50;
00092 mplan_req.motion_plan_request.planner_id = config;
00093 mplan_req.motion_plan_request.group_name = "right_arm";
00094
00095 mplan_req.motion_plan_request.allowed_planning_time = ros::Duration(15.0);
00096 const std::vector<std::string>& joint_names = scene.getRobotModel()->getJointModelGroup("right_arm")->getJointModelNames();
00097 mplan_req.motion_plan_request.goal_constraints.resize(1);
00098 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints.resize(joint_names.size());
00099
00100 for(unsigned int i = 0; i < joint_names.size(); i++)
00101 {
00102 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].joint_name = joint_names[i];
00103 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].position = 0.0;
00104 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_above = 1e-12;
00105 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_below = 1e-12;
00106 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[i].weight = 1.0;
00107 }
00108
00109 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[0].position = -0.30826385287398406;
00110 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[1].position = 0.61185361475247468;
00111 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[2].position = -0.67790861269459102;
00112 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[3].position = -1.0372591097007691;
00113 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[4].position = -0.89601966543848288;
00114 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[5].position = -1.9776217463278662;
00115 mplan_req.motion_plan_request.goal_constraints[0].joint_constraints[6].position = 1.8552611548679128;
00116
00117
00118
00119 mplan_req.motion_plan_request.start_state.joint_state.name = joint_names;
00120 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-1.21044517893021499);
00121 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(0.038959594993384528);
00122 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-0.81412902362644646);
00123 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-1.0989597173881371);
00124 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(2.3582101183671629);
00125 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-1.993988668449755);
00126 mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-2.2779628049776051);
00127
00128
00129
00130
00131
00132 moveit_msgs::Constraints &constr = mplan_req.motion_plan_request.path_constraints;
00133 constr.orientation_constraints.resize(1);
00134 moveit_msgs::OrientationConstraint &ocm = constr.orientation_constraints[0];
00135 ocm.link_name = "r_wrist_roll_link";
00136 ocm.header.frame_id = psm.getPlanningScene()->getPlanningFrame();
00137 ocm.orientation.x = 0.0;
00138 ocm.orientation.y = 0.0;
00139 ocm.orientation.z = 0.0;
00140 ocm.orientation.w = 1.0;
00141 ocm.absolute_x_axis_tolerance = 0.1;
00142 ocm.absolute_y_axis_tolerance = 0.1;
00143 ocm.absolute_z_axis_tolerance = M_PI;
00144 ocm.weight = 1.0;
00145
00146 benchmark_service_client.call(mplan_req, mplan_res);
00147 }
00148
00149 int main(int argc, char **argv)
00150 {
00151 ros::init(argc, argv, "call_ompl_planning", ros::init_options::AnonymousName);
00152 ros::AsyncSpinner spinner(1);
00153 spinner.start();
00154
00155 benchmarkPathConstrained("SBLkConfigDefault");
00156 benchmarkPathConstrained("ESTkConfigDefault");
00157 benchmarkPathConstrained("BKPIECEkConfigDefault");
00158 benchmarkPathConstrained("LBKPIECEkConfigDefault");
00159 benchmarkPathConstrained("KPIECEkConfigDefault");
00160 benchmarkPathConstrained("RRTkConfigDefault");
00161 benchmarkPathConstrained("RRTConnectkConfigDefault");
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179 return 0;
00180 }