move_arm_pose_goal.cpp
Go to the documentation of this file.
00001 //
00002 // This file has been copied from the move_arm tutorial:
00003 // http://www.ros.org/wiki/move_arm/Tutorials/MoveArmPoseGoalComplex
00004 //
00005 
00006 #include <ros/ros.h>
00007 #include <actionlib/client/simple_action_client.h>
00008 #include <move_arm_msgs/MoveArmAction.h>
00009 
00010 int main(int argc, char **argv){
00011   ros::init (argc, argv, "move_arm_joint_goal_test");
00012   ros::NodeHandle nh;
00013   actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> move_arm("move_right_arm",true);
00014 
00015   move_arm.waitForServer();
00016   ROS_INFO("Connected to server");
00017 
00018   move_arm_msgs::MoveArmGoal goalA;
00019 
00020   goalA.motion_plan_request.group_name = "right_arm";
00021   goalA.motion_plan_request.num_planning_attempts = 1;
00022   goalA.motion_plan_request.allowed_planning_time = ros::Duration(5.0);
00023 
00024   nh.param<std::string>("planner_id",goalA.motion_plan_request.planner_id,std::string(""));
00025   nh.param<std::string>("planner_service_name",goalA.planner_service_name,std::string("ompl_planning/plan_kinematic_path"));
00026   goalA.motion_plan_request.goal_constraints.set_position_constraints_size(1);
00027   goalA.motion_plan_request.goal_constraints.position_constraints[0].header.stamp = ros::Time::now();
00028   goalA.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id = "torso_lift_link";
00029     
00030   goalA.motion_plan_request.goal_constraints.position_constraints[0].link_name = "r_wrist_roll_link";
00031   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.x = 0.75;
00032   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.y = -0.188;
00033   goalA.motion_plan_request.goal_constraints.position_constraints[0].position.z = 0;
00034     
00035   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00036   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00037   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00038   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_shape.dimensions.push_back(0.02);
00039 
00040   goalA.motion_plan_request.goal_constraints.position_constraints[0].constraint_region_orientation.w = 1.0;
00041   goalA.motion_plan_request.goal_constraints.position_constraints[0].weight = 1.0;
00042 
00043   goalA.motion_plan_request.goal_constraints.set_orientation_constraints_size(1);
00044   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.stamp = ros::Time::now();
00045   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id = "torso_lift_link";    
00046   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].link_name = "r_wrist_roll_link";
00047   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.x = 0.0;
00048   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.y = 0.0;
00049   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.z = 0.0;
00050   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].orientation.w = 1.0;
00051     
00052   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_roll_tolerance = 0.04;
00053   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_pitch_tolerance = 0.04;
00054   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].absolute_yaw_tolerance = 0.04;
00055 
00056   goalA.motion_plan_request.goal_constraints.orientation_constraints[0].weight = 1.0;
00057 
00058   if (nh.ok())
00059   {
00060     bool finished_within_time = false;
00061     move_arm.sendGoal(goalA);
00062     finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00063     if (!finished_within_time)
00064     {
00065       move_arm.cancelGoal();
00066       ROS_INFO("Timed out achieving goal A");
00067     }
00068     else
00069     {
00070       actionlib::SimpleClientGoalState state = move_arm.getState();
00071       bool success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00072       if(success)
00073         ROS_INFO("Action finished: %s",state.toString().c_str());
00074       else
00075         ROS_INFO("Action failed: %s",state.toString().c_str());
00076     }
00077   }
00078   ros::shutdown();
00079 }
00080 
00081 
00082 
00083 
00084 


hrl_simple_arm_goals
Author(s): Advait Jain, Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 11:44:42