regression_test_add_object.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *  \author Sachin Chitta, Ioan Sucan
00036  *********************************************************************/
00037 
00038 #include <ros/ros.h>
00039 #include <tf/tf.h>
00040 #include <gtest/gtest.h>
00041 #include <boost/thread.hpp>
00042 #include <kinematics_msgs/GetPositionFK.h>
00043 #include <motion_planning_msgs/GetMotionPlan.h>
00044 #include <planning_environment_msgs/GetRobotState.h>
00045 
00046 #include <actionlib/client/simple_action_client.h>
00047 #include <move_arm_msgs/MoveArmAction.h>
00048 #include <geometric_shapes_msgs/Shape.h>
00049 
00050 #include <arm_navigation_tests/arm_navigation_utils.h>
00051 
00052 #include <mapping_msgs/CollisionObject.h>
00053 #include <geometric_shapes_msgs/Shape.h>
00054 
00055 void spinThread()
00056 {
00057   ros::spin();
00058 }
00059 
00060 TEST(OMPL, PathConstraintsTest)
00061 {
00062   ros::NodeHandle nh;
00063   ros::NodeHandle private_handle("~");
00064   boost::thread spin_thread(&spinThread);
00065 
00066   actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> move_arm(nh, "move_right_arm");
00067   move_arm.waitForServer();
00068   ROS_INFO("Connected to server");
00069 
00070   arm_navigation_utils::ArmNavigationUtils arm_nav_utils;
00071   EXPECT_TRUE(arm_nav_utils.takeStaticMap());
00072 
00073 
00074   ros::Publisher object_publisher = nh.advertise<mapping_msgs::CollisionObject>("collision_object", 1, true); 
00075   mapping_msgs::CollisionObject obj1;          
00076   obj1.header.stamp = ros::Time::now();
00077   obj1.header.frame_id = "base_link";
00078   obj1.id = "obj1";
00079   obj1.operation.operation = mapping_msgs::CollisionObjectOperation::ADD;
00080   obj1.shapes.resize(1);
00081   obj1.shapes[0].type = geometric_shapes_msgs::Shape::CYLINDER;
00082   obj1.shapes[0].dimensions.resize(2);
00083   obj1.shapes[0].dimensions[0] = .1;
00084   obj1.shapes[0].dimensions[1] = 1.5;
00085   obj1.poses.resize(1);
00086   obj1.poses[0].position.x = .6;
00087   obj1.poses[0].position.y = -.45;
00088   obj1.poses[0].position.z = .75;
00089   obj1.poses[0].orientation.x = 0;
00090   obj1.poses[0].orientation.y = 0;
00091   obj1.poses[0].orientation.z = 0;
00092   obj1.poses[0].orientation.w = 1;
00093 
00094   object_publisher.publish(obj1);
00095   ros::Duration(1.0).sleep();
00096 
00097   move_arm_msgs::MoveArmGoal goalA;
00098   goalA.motion_plan_request.group_name = "right_arm";
00099   goalA.motion_plan_request.num_planning_attempts = 1;
00100   private_handle.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string(""));
00101   private_handle.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("/ompl_planning/plan_kinematic_path"));
00102   goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00103     
00104   goalA.motion_plan_request.goal_constraints.position_constraints.resize(1);
00105   goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now();
00106   goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link";
00107     
00108   goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link";
00109   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75;
00110   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.188;
00111   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = 0;
00112     
00113   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00114   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00115   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00116   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00117 
00118   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00119   goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00120 
00121   goalA.motion_plan_request.goal_constraints.orientation_constraints.resize(1);
00122   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00123   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";    
00124   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link";
00125   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0;
00126   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0;
00127   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0;
00128   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0;
00129     
00130   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00131   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00132   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00133 
00134   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00135   goalA.disable_ik = true;
00136   goalA.accept_partial_plans = true;
00137   int num_test_attempts = 0;
00138   int max_attempts = 5;
00139   bool success = false;
00140   while (nh.ok())
00141   {
00142     bool finished_within_time = false;
00143     move_arm.sendGoal(goalA);
00144     finished_within_time = move_arm.waitForResult(ros::Duration(100.0));
00145     actionlib::SimpleClientGoalState state = move_arm.getState();
00146     success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00147     if ((!finished_within_time || !success) && num_test_attempts < max_attempts)
00148     {
00149       move_arm.cancelGoal();
00150       ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts);
00151       num_test_attempts++;
00152     }
00153     else
00154     {
00155       if(!success)
00156       {
00157         ROS_INFO("Action finished: %s",state.toString().c_str());
00158         move_arm.cancelGoal();
00159       }
00160       ROS_INFO("Action finished: %s",state.toString().c_str());
00161       break;
00162     }
00163   }
00164 
00165   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.46;
00166   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.678;
00167   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = -0.15;
00168 
00169   goalA.motion_plan_request.path_constraints.orientation_constraints.resize(1);
00170   goalA.motion_plan_request.path_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";
00171   goalA.motion_plan_request.path_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00172   goalA.motion_plan_request.path_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link";
00173    
00174   goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.x = 0.0;
00175   goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.y = 0.0;
00176   goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.z = 0.0;
00177   goalA.motion_plan_request.path_constraints.orientation_constraints[0].orientation.w = 1.0;
00178 
00179   goalA.motion_plan_request.path_constraints.orientation_constraints[0].type = motion_planning_msgs::OrientationConstraint::HEADER_FRAME;
00180   goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.1;
00181   goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.1;
00182   goalA.motion_plan_request.path_constraints.orientation_constraints[0].absolute_yaw_tolerance = M_PI;
00183 
00184   while (nh.ok())
00185   {
00186     bool finished_within_time = false;
00187     move_arm.sendGoal(goalA);
00188     finished_within_time = move_arm.waitForResult(ros::Duration(100.0));
00189     actionlib::SimpleClientGoalState state = move_arm.getState();
00190     success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00191     if ((!finished_within_time || !success) && num_test_attempts < max_attempts)
00192     {
00193       move_arm.cancelGoal();
00194       ROS_INFO("Timed out achieving goal A, trying again. Trying again, attempt: %d",num_test_attempts);
00195       num_test_attempts++;
00196     }
00197     else
00198     {
00199       if(!success)
00200       {
00201         ROS_INFO("Action finished: %s",state.toString().c_str());
00202         move_arm.cancelGoal();
00203       }
00204       ROS_INFO("Action finished: %s",state.toString().c_str());
00205       break;
00206     }
00207   }
00208   ros::shutdown();
00209   spin_thread.join();
00210 }
00211 
00212 int main(int argc, char **argv){
00213   testing::InitGoogleTest(&argc, argv);
00214   ros::init(argc,argv,"path_constraints_test");
00215   return RUN_ALL_TESTS();
00216 }


arm_navigation_tests
Author(s): Sachin Chitta
autogenerated on Sat Dec 28 2013 17:24:27