low_five.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 Joe Romano
00036  *********************************************************************/
00037 //@author  Joe Romano
00038 //@email   joeromano@gmail.com
00039 //@brief   low_five.cpp - pr2 gives you props yo
00040 
00041 #include <ros/ros.h>
00042 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
00043 #include <pr2_gripper_sensor_msgs/PR2GripperEventDetectorAction.h>
00044 #include <actionlib/client/simple_action_client.h>
00045 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00046 
00047 typedef actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > TrajClient;
00048 // Our Action interface type, provided as a typedef for convenience                   
00049 typedef actionlib::SimpleActionClient<pr2_gripper_sensor_msgs::PR2GripperEventDetectorAction> PlaceClient;
00050 // Our Action interface type, provided as a typedef for convenience                   
00051 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
00052 // Our Action interface type, provided as a typedef for convenience                   
00053 
00054 
00055 class RobotArm
00056 {
00057 private:
00058   // Action client for the joint trajectory action 
00059   // used to trigger the arm movement action
00060   TrajClient* traj_client_r_;
00061   TrajClient* traj_client_l_;
00062 
00063 public:
00065   RobotArm() 
00066   {
00067     // tell the action client that we want to spin a thread by default
00068     traj_client_r_ = new TrajClient("r_arm_controller/joint_trajectory_action", true);
00069     traj_client_l_ = new TrajClient("l_arm_controller/joint_trajectory_action", true);
00070 
00071     // wait for action server to come up
00072     while(!traj_client_l_->waitForServer(ros::Duration(5.0))){
00073       ROS_INFO("Waiting for the joint_trajectory_action server");
00074     }
00075     // wait for action server to come up
00076     while(!traj_client_r_->waitForServer(ros::Duration(5.0))){
00077       ROS_INFO("Waiting for the joint_trajectory_action server");
00078     }
00079   }
00080 
00082   ~RobotArm()
00083   {
00084     delete traj_client_r_;
00085     delete traj_client_l_;
00086   }
00087 
00089   void startTrajectory(pr2_controllers_msgs::JointTrajectoryGoal goal,bool right_arm)
00090   {
00091     //Start the trjaectory immediately
00092     goal.trajectory.header.stamp = ros::Time::now();
00093 
00094     if(right_arm)
00095       traj_client_r_->sendGoal(goal);
00096     else
00097       traj_client_l_->sendGoal(goal);
00098   }
00099 
00101   pr2_controllers_msgs::JointTrajectoryGoal arm_trajectoryPoint(float* angles, float duration, bool right_arm)
00102   {
00103     //our goal variable
00104     pr2_controllers_msgs::JointTrajectoryGoal goal;
00105 
00106     // First, the joint names, which apply to all waypoints
00107     //starts at 17
00108     if(right_arm)
00109     {
00110       goal.trajectory.joint_names.push_back("r_shoulder_pan_joint");
00111       goal.trajectory.joint_names.push_back("r_shoulder_lift_joint");
00112       goal.trajectory.joint_names.push_back("r_upper_arm_roll_joint");
00113       goal.trajectory.joint_names.push_back("r_elbow_flex_joint");
00114       goal.trajectory.joint_names.push_back("r_forearm_roll_joint");
00115       goal.trajectory.joint_names.push_back("r_wrist_flex_joint");
00116       goal.trajectory.joint_names.push_back("r_wrist_roll_joint");
00117     }
00118     else
00119     {
00120       goal.trajectory.joint_names.push_back("l_shoulder_pan_joint");
00121       goal.trajectory.joint_names.push_back("l_shoulder_lift_joint");
00122       goal.trajectory.joint_names.push_back("l_upper_arm_roll_joint");
00123       goal.trajectory.joint_names.push_back("l_elbow_flex_joint");
00124       goal.trajectory.joint_names.push_back("l_forearm_roll_joint");
00125       goal.trajectory.joint_names.push_back("l_wrist_flex_joint");
00126       goal.trajectory.joint_names.push_back("l_wrist_roll_joint");
00127     }
00128 
00129     // We will have N waypoints in this goal trajectory
00130     goal.trajectory.points.resize(1);
00131 
00132     // First trajectory point
00133     // Positions
00134     int ind = 0;
00135     goal.trajectory.points[ind].positions.resize(7);
00136     goal.trajectory.points[ind].positions[0] =  angles[0];
00137     goal.trajectory.points[ind].positions[1] =  angles[1];
00138     goal.trajectory.points[ind].positions[2] =  angles[2];
00139     goal.trajectory.points[ind].positions[3] =  angles[3];
00140     goal.trajectory.points[ind].positions[4] =  angles[4];
00141     goal.trajectory.points[ind].positions[5] =  angles[5];
00142     goal.trajectory.points[ind].positions[6] =  angles[6];
00143     // Velocities
00144     goal.trajectory.points[ind].velocities.resize(7);
00145     for (size_t j = 0; j < 7; ++j)
00146     {
00147       goal.trajectory.points[ind].velocities[j] = 0.0;
00148     }
00149     // set time we want this trajectory to be reached at
00150     goal.trajectory.points[ind].time_from_start = ros::Duration(duration);
00151 
00152     //we are done; return the goal
00153     return goal;
00154   }
00155 
00156 
00158   //actionlib::SimpleClientGoalState getState()
00159   //{
00160   //  return traj_client_->getState();
00161   //}
00162 };
00163 
00164 
00165 class Gripper{
00166 private:
00167   GripperClient* gripper_client_r_, *gripper_client_l_;  
00168   PlaceClient* place_client_r_, *place_client_l_;
00169 
00170 public:
00171   //Action client initialization
00172   Gripper(){
00173 
00174     //Initialize the client for the Action interface to the gripper controller
00175     //and tell the action client that we want to spin a thread by default
00176     gripper_client_l_  = new GripperClient("l_gripper_sensor_controller/gripper_action",true);
00177     place_client_l_  = new PlaceClient("l_gripper_sensor_controller/event_detector",true);
00178     gripper_client_r_  = new GripperClient("r_gripper_sensor_controller/gripper_action",true);
00179     place_client_r_  = new PlaceClient("r_gripper_sensor_controller/event_detector",true);
00180     
00181     //wait for the gripper action server to come up 
00182     while(!gripper_client_r_->waitForServer(ros::Duration(5.0))){
00183       ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
00184     }
00185 
00186     while(!place_client_r_->waitForServer(ros::Duration(5.0))){
00187       ROS_INFO("Waiting for the r_gripper_sensor_controller/event_detector action server to come up");
00188     }    
00189 
00190     //wait for the gripper action server to come up 
00191     while(!gripper_client_l_->waitForServer(ros::Duration(5.0))){
00192       ROS_INFO("Waiting for the l_gripper_sensor_controller/gripper_action action server to come up");
00193     }
00194 
00195     while(!place_client_l_->waitForServer(ros::Duration(5.0))){
00196       ROS_INFO("Waiting for the l_gripper_sensor_controller/event_detector action server to come up");
00197     }    
00198 
00199 
00200   }
00201 
00202   ~Gripper(){
00203     delete gripper_client_l_;
00204     delete gripper_client_r_;
00205     delete place_client_l_;
00206     delete place_client_r_;
00207 
00208 
00209   }
00210 
00211   
00212 
00213 
00214   //Open the gripper
00215   void open(bool left, bool right){
00216     pr2_controllers_msgs::Pr2GripperCommandGoal open;
00217     open.command.position = 0.09;    // position open (9 cm)
00218     open.command.max_effort = -1.0;  // Do not limit effort (negative)
00219     
00220     if(left)
00221       gripper_client_l_->sendGoal(open);
00222     if(right)
00223       gripper_client_r_->sendGoal(open);
00224   }
00225 
00226   //Close the gripper
00227   void close(bool left, bool right,bool wait_for_result){
00228     pr2_controllers_msgs::Pr2GripperCommandGoal close;
00229     close.command.position = 0.002;    // position open (9 cm)
00230     close.command.max_effort = -1.0;  // Do not limit effort (negative)
00231     
00232     if(left)
00233     {
00234       gripper_client_l_->sendGoal(close);
00235       if(wait_for_result)
00236         gripper_client_l_->waitForResult();
00237     }
00238     if(right)
00239     {
00240       gripper_client_r_->sendGoal(close);
00241       if(wait_for_result)
00242         gripper_client_r_->waitForResult();
00243     }
00244   }
00245 
00246 
00247   //move into place mode to drop an object
00248   void slap(bool left, bool right){
00249     pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal place_goal;
00250     place_goal.command.trigger_conditions = 4;  // just use acceleration as a trigger
00251     place_goal.command.acceleration_trigger_magnitude = 6.0;
00252     place_goal.command.slip_trigger_magnitude = 0.008;
00253 
00254     if(left)
00255       place_client_l_->sendGoal(place_goal);
00256     if(right)
00257       place_client_r_->sendGoal(place_goal);
00258   }
00259 
00261   bool slapDone(bool left, bool right)
00262   {
00263     if(left && right)
00264       return place_client_l_->getState().isDone() && place_client_r_->getState().isDone();
00265     else if(left)
00266       return place_client_l_->getState().isDone();
00267     else if(right)
00268       return place_client_r_->getState().isDone();
00269     return false;
00270   }  
00271 };
00272 
00273 int main(int argc, char** argv){
00274   ros::init(argc, argv, "lift_test");
00275 
00276   // figure out what kind of five we want
00277   bool left = false;
00278   bool right = true;
00279   if(argc > 1)
00280   {
00281     left =  (strcmp(argv[1],"left") == 0);
00282     right = (strcmp(argv[1],"right") == 0);
00283   }
00284 
00285 
00286 
00287   RobotArm arm;
00288   Gripper gripper;
00289 
00290   gripper.close(left,right,true);
00291   
00292   float pre_gameday_r []= {-1.1036096831987545, 1.2273993160398446, 0.17540433749819506, -1.9961097303847053, -25.599756786728236, -0.64634984121557015, -22.883812446893003};
00293   float pre_gameday_l []= {1.4465628676193982, 1.2285750945849796, 0.40253450962996462, -2.0440306850200791, -31.168929834115303, -0.60889826357579968, 4.0359526956896818};
00294     if(left)
00295       arm.startTrajectory(arm.arm_trajectoryPoint(pre_gameday_l,2.0,false),false);
00296     if(right)
00297       arm.startTrajectory(arm.arm_trajectoryPoint(pre_gameday_r,2.0,true),true);
00298     sleep(2.0);
00299 
00300     float gameday_r []= {-0.12240986677882781, 0.98503486134558194, -0.37204703972859665, -1.2757306705402713, -25.884133066177196, -0.098050430120481424, -22.538873728343418};
00301     float gameday_l []= {0.1132586472843532, 0.84772875076872478, 0.5973656236693764, -1.1092462016166407, -31.294862942406674, -0.082788401731504702, 4.2950048059626678};
00302     if(left)
00303       arm.startTrajectory(arm.arm_trajectoryPoint(gameday_l,1.75,false),false);
00304     if(right)
00305       arm.startTrajectory(arm.arm_trajectoryPoint(gameday_r,1.75,true),true);
00306 
00307     // now start looking for a slap during the move
00308     gripper.slap(left,right);
00309 
00310 
00311     //wait for a slap
00312     while(!gripper.slapDone(left,right) && ros::ok())
00313     {
00314       ros::Duration(0.005).sleep();
00315     }
00316 
00317 
00318     if(left)
00319       arm.startTrajectory(arm.arm_trajectoryPoint(pre_gameday_l,1.35,false),false);
00320     if(right)
00321       arm.startTrajectory(arm.arm_trajectoryPoint(pre_gameday_r,1.35,true),true);
00322     //system("rosrun pr2_pose_saver load.py ./saved_poses/post_five.pps -s 1.0");
00323 
00324 
00325   return 0;
00326 }


pr2_props
Author(s): Joe Romano
autogenerated on Fri Aug 28 2015 12:13:27