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 <moveit_msgs/ComputePlanningBenchmark.h>
00039 #include <kinematic_constraints/utils.h>
00040
00041 static const std::string ROBOT_DESCRIPTION="robot_description";
00042 static const std::string BENCHMARK_SERVICE_NAME="benchmark_planning_problem";
00043
00044 int main(int argc, char **argv)
00045 {
00046 ros::init(argc, argv, "call_moveit_benchmark", ros::init_options::AnonymousName);
00047
00048 ros::AsyncSpinner spinner(1);
00049 spinner.start();
00050
00051
00052 moveit_msgs::ComputePlanningBenchmark::Request req;
00053 moveit_msgs::ComputePlanningBenchmark::Request res;
00054
00055
00056 boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener());
00057 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION, tf);
00058
00059 Eigen::Affine3d t;
00060 t = Eigen::Translation3d(0.45, -0.45, 0.7);
00061 psm.getPlanningScene()->getWorldNonConst()->addToObject("pole", shapes::ShapePtr(new shapes::Box(0.1, 0.1, 1.4)), t);
00062
00063 if (psm.getPlanningScene()->isConfigured())
00064 psm.getPlanningScene()->getPlanningSceneMsg(req.scene);
00065 req.motion_plan_request.start_state = req.scene.robot_state;
00066
00067
00068 req.default_average_count = 10;
00069 req.filename = "benchmark_results.log";
00070
00071
00072 req.motion_plan_request.group_name = "right_arm";
00073 req.motion_plan_request.num_planning_attempts = 1;
00074 req.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00075
00076 const std::vector<std::string>& joint_names = psm.getPlanningScene()->getRobotModel()->getJointModelGroup("right_arm")->getJointModelNames();
00077 req.motion_plan_request.goal_constraints.resize(1);
00078 req.motion_plan_request.goal_constraints[0].joint_constraints.resize(joint_names.size());
00079 for(unsigned int i = 0; i < joint_names.size(); i++)
00080 {
00081 req.motion_plan_request.goal_constraints[0].joint_constraints[i].joint_name = joint_names[i];
00082 req.motion_plan_request.goal_constraints[0].joint_constraints[i].position = 0.0;
00083 req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_above = 0.001;
00084 req.motion_plan_request.goal_constraints[0].joint_constraints[i].tolerance_below = 0.001;
00085 req.motion_plan_request.goal_constraints[0].joint_constraints[i].weight = 1.0;
00086 }
00087 req.motion_plan_request.goal_constraints[0].joint_constraints[0].position = -2.0;
00088 req.motion_plan_request.goal_constraints[0].joint_constraints[3].position = -.2;
00089 req.motion_plan_request.goal_constraints[0].joint_constraints[5].position = -.2;
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105 req.planner_interfaces.resize(1);
00106 req.planner_interfaces[0].name = "ompl_interface_ros/OMPLPlanner";
00107
00108 ros::NodeHandle nh;
00109 ros::service::waitForService(BENCHMARK_SERVICE_NAME);
00110 ros::ServiceClient benchmark_service_client = nh.serviceClient<moveit_msgs::ComputePlanningBenchmark>(BENCHMARK_SERVICE_NAME);
00111 if (!benchmark_service_client.call(req, res))
00112 ROS_ERROR("Error calling benchmark service");
00113
00114 ros::waitForShutdown();
00115
00116 return 0;
00117 }