hug.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   hug.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 
00056 class RobotArm
00057 {
00058 private:
00059   // Action client for the joint trajectory action 
00060   // used to trigger the arm movement action
00061   TrajClient* traj_client_r_;
00062   TrajClient* traj_client_l_;
00063 
00064 public:
00066   RobotArm() 
00067   {
00068     // tell the action client that we want to spin a thread by default
00069     traj_client_r_ = new TrajClient("r_arm_controller/joint_trajectory_action", true);
00070     traj_client_l_ = new TrajClient("l_arm_controller/joint_trajectory_action", true);
00071 
00072     // wait for action server to come up
00073     while(!traj_client_l_->waitForServer(ros::Duration(5.0))){
00074       ROS_INFO("Waiting for the joint_trajectory_action server");
00075     }
00076     // wait for action server to come up
00077     while(!traj_client_r_->waitForServer(ros::Duration(5.0))){
00078       ROS_INFO("Waiting for the joint_trajectory_action server");
00079     }
00080   }
00081 
00083   ~RobotArm()
00084   {
00085     delete traj_client_r_;
00086     delete traj_client_l_;
00087   }
00088 
00090   void startTrajectory(pr2_controllers_msgs::JointTrajectoryGoal goal,bool right_arm)
00091   {
00092     //Start the trjaectory immediately
00093     goal.trajectory.header.stamp = ros::Time::now();
00094 
00095     if(right_arm)
00096       traj_client_r_->sendGoal(goal);
00097     else
00098       traj_client_l_->sendGoal(goal);
00099   }
00100 
00102   pr2_controllers_msgs::JointTrajectoryGoal arm_trajectoryPoint(float* angles, float duration, bool right_arm)
00103   {
00104     //our goal variable
00105     pr2_controllers_msgs::JointTrajectoryGoal goal;
00106 
00107     // First, the joint names, which apply to all waypoints
00108     //starts at 17
00109     if(right_arm)
00110     {
00111       goal.trajectory.joint_names.push_back("r_shoulder_pan_joint");
00112       goal.trajectory.joint_names.push_back("r_shoulder_lift_joint");
00113       goal.trajectory.joint_names.push_back("r_upper_arm_roll_joint");
00114       goal.trajectory.joint_names.push_back("r_elbow_flex_joint");
00115       goal.trajectory.joint_names.push_back("r_forearm_roll_joint");
00116       goal.trajectory.joint_names.push_back("r_wrist_flex_joint");
00117       goal.trajectory.joint_names.push_back("r_wrist_roll_joint");
00118     }
00119     else
00120     {
00121       goal.trajectory.joint_names.push_back("l_shoulder_pan_joint");
00122       goal.trajectory.joint_names.push_back("l_shoulder_lift_joint");
00123       goal.trajectory.joint_names.push_back("l_upper_arm_roll_joint");
00124       goal.trajectory.joint_names.push_back("l_elbow_flex_joint");
00125       goal.trajectory.joint_names.push_back("l_forearm_roll_joint");
00126       goal.trajectory.joint_names.push_back("l_wrist_flex_joint");
00127       goal.trajectory.joint_names.push_back("l_wrist_roll_joint");
00128     }
00129 
00130     // We will have N waypoints in this goal trajectory
00131     goal.trajectory.points.resize(1);
00132 
00133     // First trajectory point
00134     // Positions
00135     int ind = 0;
00136     goal.trajectory.points[ind].positions.resize(7);
00137     goal.trajectory.points[ind].positions[0] =  angles[0];
00138     goal.trajectory.points[ind].positions[1] =  angles[1];
00139     goal.trajectory.points[ind].positions[2] =  angles[2];
00140     goal.trajectory.points[ind].positions[3] =  angles[3];
00141     goal.trajectory.points[ind].positions[4] =  angles[4];
00142     goal.trajectory.points[ind].positions[5] =  angles[5];
00143     goal.trajectory.points[ind].positions[6] =  angles[6];
00144     // Velocities
00145     goal.trajectory.points[ind].velocities.resize(7);
00146     for (size_t j = 0; j < 7; ++j)
00147     {
00148       goal.trajectory.points[ind].velocities[j] = 0.0;
00149     }
00150     // set time we want this trajectory to be reached at
00151     goal.trajectory.points[ind].time_from_start = ros::Duration(duration);
00152 
00153     //we are done; return the goal
00154     return goal;
00155   }
00156 
00157 
00159   //actionlib::SimpleClientGoalState getState()
00160   //{
00161   //  return traj_client_->getState();
00162   //}
00163 };
00164 
00165 
00166 class Gripper{
00167 private:
00168   GripperClient* gripper_client_r_, *gripper_client_l_;  
00169   PlaceClient* place_client_r_, *place_client_l_;
00170 
00171 
00172 public:
00173   //Action client initialization
00174   Gripper(){
00175 
00176     //Initialize the client for the Action interface to the gripper controller
00177     //and tell the action client that we want to spin a thread by default
00178     gripper_client_l_  = new GripperClient("l_gripper_sensor_controller/gripper_action",true);
00179     place_client_l_  = new PlaceClient("l_gripper_sensor_controller/event_detector",true);
00180     gripper_client_r_  = new GripperClient("r_gripper_sensor_controller/gripper_action",true);
00181     place_client_r_  = new PlaceClient("r_gripper_sensor_controller/event_detector",true);
00182         
00183     //wait for the gripper action server to come up 
00184     while(!gripper_client_r_->waitForServer(ros::Duration(5.0))){
00185       ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
00186     }
00187 
00188     while(!place_client_r_->waitForServer(ros::Duration(5.0))){
00189       ROS_INFO("Waiting for the r_gripper_sensor_controller/event_detector action server to come up");
00190     }    
00191 
00192     //wait for the gripper action server to come up 
00193     while(!gripper_client_l_->waitForServer(ros::Duration(5.0))){
00194       ROS_INFO("Waiting for the l_gripper_sensor_controller/gripper_action action server to come up");
00195     }
00196 
00197     while(!place_client_l_->waitForServer(ros::Duration(5.0))){
00198       ROS_INFO("Waiting for the l_gripper_sensor_controller/event_detector action server to come up");
00199     }    
00200 
00201 
00202   }
00203 
00204   ~Gripper(){
00205     delete gripper_client_l_;
00206     delete gripper_client_r_;
00207     delete place_client_l_;
00208     delete place_client_r_;
00209 
00210 
00211   }
00212 
00213   
00214 
00215   //Close the gripper
00216   void close(){
00217     pr2_controllers_msgs::Pr2GripperCommandGoal close;
00218     close.command.position = 0.002;    // position open (9 cm)
00219     close.command.max_effort = -1.0;  // Do not limit effort (negative)
00220     
00221     gripper_client_l_->sendGoal(close);
00222     gripper_client_r_->sendGoal(close);
00223   }
00224 
00225 
00226   //move into place mode to drop an object
00227   void slap()
00228   {
00229     pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal place_goal;
00230     place_goal.command.trigger_conditions = 4;  // use just acceleration as our contact signal
00231     place_goal.command.acceleration_trigger_magnitude = 1.5;  // m/^2
00232     place_goal.command.slip_trigger_magnitude = 0.008;        // slip gain
00233 
00234     place_client_l_->sendGoal(place_goal);
00235     place_client_r_->sendGoal(place_goal);
00236   }
00237 
00239   bool slapDone()
00240   {
00241     return (place_client_l_->getState().isDone() || place_client_r_->getState().isDone());
00242   }  
00243 };
00244 
00245 int main(int argc, char** argv){
00246   ros::init(argc, argv, "lift_test");
00247 
00248 
00249   RobotArm arm;
00250   Gripper gripper;
00251 
00252   gripper.close();
00253   
00254     float pre_five_r []= {-1.2440268659190405, -0.28289966142917794, -1.1217752376321288, -1.2193909991875618, -0.060409905659649613, -0.51368910051651173, 0.13883178895127068 };
00255     float pre_five_l []= {1.2108476211884767, -0.25952982735485397, 1.0790306213975294, -1.1914537633376514, 0.6596898457005399, -0.49835267009274514, -0.86128687904407775};
00256       arm.startTrajectory(arm.arm_trajectoryPoint(pre_five_l,1.0,false),false);
00257       arm.startTrajectory(arm.arm_trajectoryPoint(pre_five_r,1.0,true),true);
00258 
00259     sleep(2.0);
00260 
00261     // now start looking for a slap during the move
00262     gripper.slap();
00263 
00264     //wait for a slap
00265     while(!gripper.slapDone() && ros::ok())
00266     {
00267       ros::Duration(0.005).sleep();
00268     }
00269 
00270 
00271 
00272 
00273     float five_r []= {-0.18497773580090426, -0.19788176370920113, -1.2492573245961882, -1.57552694919104, 0.022542817027454143, -0.48649602545426462, 0.11102958900762983 };
00274     float five_l []= {0.17136445276658918, 0.046957579052585213, 1.2156529334646724, -1.3449107174041908, 1.2175671522517455, -1.3348986768476458, -0.83435485750242855};
00275       arm.startTrajectory(arm.arm_trajectoryPoint(five_l,3.0,false),false);
00276       arm.startTrajectory(arm.arm_trajectoryPoint(five_r,3.0,true),true);
00277 
00278     sleep(5.5);
00279 
00280     float post_five_r []= {-1.2440268659190405, -0.28289966142917794, -1.1217752376321288, -1.2193909991875618, -0.060409905659649613, -0.51368910051651173, 0.13883178895127068 };
00281     float post_five_l []= {1.2108476211884767, -0.25952982735485397, 1.0790306213975294, -1.1914537633376514, 0.6596898457005399, -0.49835267009274514, -0.86128687904407775};
00282       arm.startTrajectory(arm.arm_trajectoryPoint(post_five_l,2.0,false),false);
00283       arm.startTrajectory(arm.arm_trajectoryPoint(post_five_r,2.0,true),true);
00284 
00285   return 0;
00286 }


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