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 <gtest/gtest.h>
00038 #include <planning_scene_monitor/planning_scene_monitor.h>
00039 #include <ompl_interface_ros/ompl_interface_ros.h>
00040 #include <moveit_msgs/GetMotionPlan.h>
00041 #include <moveit_msgs/DisplayTrajectory.h>
00042 #include <kinematic_constraints/utils.h>
00043 #include <planning_models/conversions.h>
00044
00045 static const std::string PLANNER_SERVICE_NAME="/ompl_planning/plan_kinematic_path";
00046 static const std::string ROBOT_DESCRIPTION="robot_description";
00047
00048 TEST(OmplPlanning, SimplePlan)
00049 {
00050 ros::NodeHandle nh;
00051 ros::service::waitForService(PLANNER_SERVICE_NAME);
00052 ros::Publisher pub = nh.advertise<moveit_msgs::DisplayTrajectory>("display_motion_plan", 1);
00053
00054 ros::ServiceClient planning_service_client = nh.serviceClient<moveit_msgs::GetMotionPlan>(PLANNER_SERVICE_NAME);
00055 EXPECT_TRUE(planning_service_client.exists());
00056 EXPECT_TRUE(planning_service_client.isValid());
00057
00058 moveit_msgs::GetMotionPlan::Request mplan_req;
00059 moveit_msgs::GetMotionPlan::Response mplan_res;
00060
00061 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00062 planning_scene::PlanningScene &scene = *psm.getPlanningScene();
00063 EXPECT_TRUE(scene.isConfigured());
00064
00065 mplan_req.motion_plan_request.planner_id = "msRRTConnectkConfigDefault";
00066 mplan_req.motion_plan_request.group_name = "whole_body";
00067 mplan_req.motion_plan_request.num_planning_attempts = 1;
00068 mplan_req.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00069 planning_models::RobotState *start = scene.getCurrentState();
00070 planning_models::robotStateToRobotStateMsg(start, mplan_req.motion_plan_request.start_state);
00071
00072 start.getJointStateGroup("right_arm")->setToRandomValues();
00073 mplan_req.motion_plan_request.goal_constraints.resize(1);
00074 mplan_req.motion_plan_request.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(start.getJointStateGroup("right_arm"));
00075 std::cout << mplan_req.motion_plan_request << std::endl;
00076
00077 ASSERT_TRUE(planning_service_client.call(mplan_req, mplan_res));
00078 ASSERT_EQ(mplan_res.error_code.val, mplan_res.error_code.SUCCESS);
00079 EXPECT_GT(mplan_res.trajectory.joint_trajectory.points.size(), 0);
00080
00081 moveit_msgs::DisplayTrajectory d;
00082 d.model_id = scene.getRobotModel()->getName();
00083 d.trajectory_start = mplan_res.trajectory_start;
00084 d.trajectory = mplan_res.trajectory;
00085 pub.publish(d);
00086 ros::Duration(0.5).sleep();
00087 }
00088
00089 int main(int argc, char **argv)
00090 {
00091 testing::InitGoogleTest(&argc, argv);
00092
00093 ros::init(argc, argv, "test_ompl_planning", ros::init_options::AnonymousName);
00094 ros::AsyncSpinner spinner(1);
00095 spinner.start();
00096
00097 return RUN_ALL_TESTS();
00098 }