00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2012, 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 the 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 <actionlib/client/simple_action_client.h> 00038 #include <moveit_msgs/MoveGroupAction.h> 00039 #include <kinematic_constraints/utils.h> 00040 #include <planning_scene_monitor/planning_scene_monitor.h> 00041 00042 static const std::string ROBOT_DESCRIPTION="robot_description"; 00043 00044 int main(int argc, char **argv) 00045 { 00046 ros::init(argc, argv, "pr2_move_group_test", ros::init_options::AnonymousName); 00047 00048 ros::AsyncSpinner spinner(1); 00049 spinner.start(); 00050 00051 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION); 00052 planning_scene::PlanningScene &scene = *psm.getPlanningScene(); 00053 00054 actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction> act("move_group", false); 00055 act.waitForServer(); 00056 00057 00058 moveit_msgs::MoveGroupGoal goal; 00059 /* 00060 goal.request.group_name = ""; 00061 goal.request.allowed_planning_time = ros::Duration(0.5); 00062 goal.request.goal_constraints.resize(1); 00063 goal.request.goal_constraints[0].joint_constraints.resize(1); 00064 goal.request.goal_constraints[0].joint_constraints[0].position = -2.0; 00065 goal.request.goal_constraints[0].joint_constraints[0].joint_name = "r_shoulder_pan_joint"; 00066 goal.request.goal_constraints[0].joint_constraints[0].position = 0.0; 00067 goal.request.goal_constraints[0].joint_constraints[0].tolerance_above = 0.001; 00068 goal.request.goal_constraints[0].joint_constraints[0].tolerance_below = 0.001; 00069 goal.request.goal_constraints[0].joint_constraints[0].weight = 1.0; 00070 */ 00071 00072 00073 00074 goal.request.group_name = "right_arm"; 00075 goal.request.num_planning_attempts = 1; 00076 goal.request.allowed_planning_time = ros::Duration(5.0); 00077 00078 geometry_msgs::PoseStamped pose; 00079 pose.header.frame_id = "torso_lift_link"; 00080 pose.pose.position.x = 0.75; 00081 pose.pose.position.y = -0.2; 00082 pose.pose.position.z = 0.0; 00083 pose.pose.orientation.x = 0.0; 00084 pose.pose.orientation.y = 0.0; 00085 pose.pose.orientation.z = 0.0; 00086 pose.pose.orientation.w = 1.0; 00087 moveit_msgs::Constraints g0 = kinematic_constraints::constructGoalConstraints("r_wrist_roll_link", pose); 00088 00089 /* 00090 pose.pose.position.x = 0.35; 00091 pose.pose.position.y = -0.6; 00092 pose.pose.position.z = 1.25; 00093 pose.pose.orientation.x = 0.0; 00094 pose.pose.orientation.y = 0.0; 00095 pose.pose.orientation.z = 0.0; 00096 pose.pose.orientation.w = 1.0; 00097 moveit_msgs::Constraints g1 = kinematic_constraints::constructGoalConstraints("r_wrist_roll_link", pose); 00098 */ 00099 goal.request.goal_constraints.resize(1); 00100 goal.request.goal_constraints[0] = g0; 00101 00102 // goal.request.goal_constraints[0] = kinematic_constraints::mergeConstraints(g1, g0); 00103 00104 planning_models::RobotState *start = scene.getCurrentState(); 00105 00106 for (int i = 0 ; i < 50 ; ++i){ 00107 start.getJointStateGroup("right_arm")->setToRandomValues(); 00108 goal.request.goal_constraints.resize(1); 00109 goal.request.goal_constraints[0] = kinematic_constraints::constructGoalConstraints(start.getJointStateGroup("right_arm")); 00110 00111 act.sendGoal(goal); 00112 if(!act.waitForResult(ros::Duration(5.0))) { 00113 ROS_INFO_STREAM("Apparently returned early"); 00114 } 00115 if (act.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) 00116 ROS_INFO("It worked!"); 00117 else 00118 ROS_WARN_STREAM("Fail: " << act.getState().toString() << ": " << act.getState().getText()); 00119 std::cout << *act.getResult() << std::endl; 00120 sleep(5); 00121 } 00122 return 0; 00123 }