test_path_constrained_plan.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 <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 
00044 static const std::string PLANNER_SERVICE_NAME="/ompl_planning/plan_kinematic_path";
00045 static const std::string ROBOT_DESCRIPTION="robot_description";
00046 
00047 TEST(OmplPlanning, PathConstrainedSimplePlan)
00048 {
00049   ros::NodeHandle nh;
00050   ros::service::waitForService(PLANNER_SERVICE_NAME);
00051   ros::Publisher pub = nh.advertise<moveit_msgs::DisplayTrajectory>("display_motion_plan", 1);
00052 
00053   ros::ServiceClient planning_service_client = nh.serviceClient<moveit_msgs::GetMotionPlan>(PLANNER_SERVICE_NAME);
00054   EXPECT_TRUE(planning_service_client.exists());
00055   EXPECT_TRUE(planning_service_client.isValid());
00056 
00057   moveit_msgs::GetMotionPlan::Request mplan_req;
00058   moveit_msgs::GetMotionPlan::Response mplan_res;
00059 
00060   planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00061   planning_scene::PlanningScene &scene = *psm.getPlanningScene();
00062   EXPECT_TRUE(scene.isConfigured());
00063 
00064   mplan_req.motion_plan_request.planner_id = "RRTConnectkConfigDefault";
00065   mplan_req.motion_plan_request.group_name = "right_arm";
00066   mplan_req.motion_plan_request.num_planning_attempts = 1;
00067   mplan_req.motion_plan_request.allowed_planning_time = ros::Duration(15.0);
00068   const std::vector<std::string>& joint_names = scene.getRobotModel()->getJointModelGroup("right_arm")->getJointModelNames();
00069 
00070   mplan_req.motion_plan_request.start_state.joint_state.name = joint_names;
00071   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-1.21044517893021499);
00072   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(0.038959594993384528);
00073   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-0.81412902362644646);
00074   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-1.0989597173881371);
00075   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(2.3582101183671629);
00076   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-1.993988668449755);
00077   mplan_req.motion_plan_request.start_state.joint_state.position.push_back(-2.2779628049776051);
00078 
00079 
00080   moveit_msgs::PositionConstraint pcm;
00081   pcm.link_name = "r_wrist_roll_link";
00082   pcm.header.frame_id = psm.getPlanningScene()->getPlanningFrame();
00083 
00084   pcm.constraint_region.primitive_poses.resize(1);
00085   pcm.constraint_region.primitive_poses[0].position.x = 0.5;
00086   pcm.constraint_region.primitive_poses[0].position.y = 0.0;
00087   pcm.constraint_region.primitive_poses[0].position.z = 0.7;
00088   pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
00089 
00090   pcm.constraint_region.primitives.resize(1);
00091   pcm.constraint_region.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00092   pcm.constraint_region.primitives[0].dimensions.x = 0.1;
00093   pcm.constraint_region.primitives[0].dimensions.y = 0.1;
00094   pcm.constraint_region.primitives[0].dimensions.z = 0.1;
00095   pcm.weight = 1.0;
00096   mplan_req.motion_plan_request.goal_constraints.resize(1);
00097   mplan_req.motion_plan_request.goal_constraints[0].position_constraints.push_back(pcm);
00098 
00099 
00100   // add path constraints
00101   moveit_msgs::Constraints &constr = mplan_req.motion_plan_request.path_constraints;
00102   constr.orientation_constraints.resize(1);
00103   moveit_msgs::OrientationConstraint &ocm = constr.orientation_constraints[0];
00104   ocm.link_name = "r_wrist_roll_link";
00105   ocm.header.frame_id = psm.getPlanningScene()->getPlanningFrame();
00106   ocm.orientation.x = 0.0;
00107   ocm.orientation.y = 0.0;
00108   ocm.orientation.z = 0.0;
00109   ocm.orientation.w = 1.0;
00110   ocm.absolute_x_axis_tolerance = 0.15;
00111   ocm.absolute_y_axis_tolerance = 0.15;
00112   ocm.absolute_z_axis_tolerance = M_PI;
00113   ocm.weight = 1.0;
00114   std::cout << mplan_req.motion_plan_request << std::endl;
00115 
00116   ASSERT_TRUE(planning_service_client.call(mplan_req, mplan_res));
00117   ASSERT_EQ(mplan_res.error_code.val, mplan_res.error_code.SUCCESS);
00118   EXPECT_GT(mplan_res.trajectory.joint_trajectory.points.size(), 0);
00119 
00120 
00121   moveit_msgs::DisplayTrajectory d;
00122   d.model_id = scene.getRobotModel()->getName();
00123   d.trajectory_start = mplan_res.trajectory_start;
00124   d.trajectory = mplan_res.trajectory;
00125   pub.publish(d);
00126   ros::Duration(0.5).sleep();
00127 }
00128 
00129 int main(int argc, char **argv)
00130 {
00131   testing::InitGoogleTest(&argc, argv);
00132 
00133   ros::init(argc, argv, "test_ompl_planning", ros::init_options::AnonymousName);
00134   ros::AsyncSpinner spinner(1);
00135   spinner.start();
00136 
00137   return RUN_ALL_TESTS();
00138 }


pr2_ompl_planning_tests
Author(s): Ioan Sucan
autogenerated on Mon Sep 14 2015 14:17:38