00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
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
00049 typedef actionlib::SimpleActionClient<pr2_gripper_sensor_msgs::PR2GripperEventDetectorAction> PlaceClient;
00050
00051 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
00052
00053
00054
00055
00056 class RobotArm
00057 {
00058 private:
00059
00060
00061 TrajClient* traj_client_r_;
00062 TrajClient* traj_client_l_;
00063
00064 public:
00066 RobotArm()
00067 {
00068
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
00073 while(!traj_client_l_->waitForServer(ros::Duration(5.0))){
00074 ROS_INFO("Waiting for the joint_trajectory_action server");
00075 }
00076
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
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
00105 pr2_controllers_msgs::JointTrajectoryGoal goal;
00106
00107
00108
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
00131 goal.trajectory.points.resize(1);
00132
00133
00134
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
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
00151 goal.trajectory.points[ind].time_from_start = ros::Duration(duration);
00152
00153
00154 return goal;
00155 }
00156
00157
00159
00160
00161
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
00174 Gripper(){
00175
00176
00177
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
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
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 void open(bool left, bool right){
00216 pr2_controllers_msgs::Pr2GripperCommandGoal open;
00217 open.command.position = 0.09;
00218 open.command.max_effort = -1.0;
00219
00220 if(left)
00221 gripper_client_l_->sendGoal(open);
00222 if(right)
00223 gripper_client_r_->sendGoal(open);
00224 }
00225
00226
00227 void close(bool left, bool right,bool wait_for_result){
00228 pr2_controllers_msgs::Pr2GripperCommandGoal close;
00229 close.command.position = 0.002;
00230 close.command.max_effort = -1.0;
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
00248 void slap(bool left, bool right){
00249 pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal place_goal;
00250 place_goal.command.trigger_conditions = 4;
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
00260
00262 bool slapDone(bool left, bool right)
00263 {
00264 if(left && right)
00265 return place_client_l_->getState().isDone() && place_client_r_->getState().isDone();
00266 else if(left)
00267 return place_client_l_->getState().isDone();
00268 else if(right)
00269 return place_client_r_->getState().isDone();
00270 return false;
00271 }
00272 };
00273
00274 int main(int argc, char** argv){
00275 ros::init(argc, argv, "lift_test");
00276
00277
00278 bool left = false;
00279 bool right = true;
00280 bool explode = false;
00281 if(argc > 1)
00282 {
00283 left = (strcmp(argv[1],"left") == 0) || (strcmp(argv[1],"double") == 0);
00284 right = (strcmp(argv[1],"right") == 0) || (strcmp(argv[1],"double") == 0);
00285 explode = (strcmp(argv[1],"explosion") == 0) || (strcmp(argv[1],"explode") == 0);
00286 }
00287
00288 if(argc > 2)
00289 {
00290 explode = (strcmp(argv[2],"explosion") == 0) || (strcmp(argv[2],"explode") == 0);
00291 }
00292
00293 RobotArm arm;
00294 Gripper gripper;
00295
00296 gripper.close(left,right,true);
00297
00298 float pre_pound_r []= {-1.6107494615714364, 0.19847126632036238, -0.54811663908273167, -2.1214811664428406, -26.842196520252376, -0.99450821985252458, -21.61195969454166 };
00299 float pre_pound_l []= {1.5734928987929435, 0.24913507488160364, 0.47068531083716647, -2.0213016833328652, -29.657732534618862, -1.2512639599262112, 3.0362047296412027};
00300 if(left)
00301 arm.startTrajectory(arm.arm_trajectoryPoint(pre_pound_l,2.0,false),false);
00302 if(right)
00303 arm.startTrajectory(arm.arm_trajectoryPoint(pre_pound_r,2.0,true),true);
00304 sleep(2.0);
00305
00306 float pound_r []= {-0.28009825299181468, 0.067518325354666564, -0.77213233152146266, -1.2593715801539329, -28.108816336121851, -0.98658959639439847, -21.203323916966269 };
00307 float pound_l []= {0.086396903260689828, 0.0093930628035789974, 0.8082322203457768, -1.1261843748485134, -28.440282742657363, -0.98277041399161458, 2.3537673178790639};
00308 if(left)
00309 arm.startTrajectory(arm.arm_trajectoryPoint(pound_l,1.75,false),false);
00310 if(right)
00311 arm.startTrajectory(arm.arm_trajectoryPoint(pound_r,1.75,true),true);
00312
00313
00314 gripper.slap(left,right);
00315
00316
00317
00318 while(!gripper.slapDone(left,right) && ros::ok())
00319 {
00320 ros::Duration(0.005).sleep();
00321 }
00322 if(explode)
00323 gripper.open(left,right);
00324
00325 float post_pound_r []= {-1.5787475072716397, 0.19686396278137783, -0.47916406374368048, -2.077760411605015, -27.01689472284307, -0.1002258761254613, -21.698716481220252};
00326 float post_pound_l []= {1.5608081863373247, 0.22663282533581869, 0.39820492931797768, -2.0037844272554586, -29.59057206666926, -0.10184530873512665, 3.0603956892165773};
00327 if(left)
00328 arm.startTrajectory(arm.arm_trajectoryPoint(post_pound_l,1.35,false),false);
00329 if(right)
00330 arm.startTrajectory(arm.arm_trajectoryPoint(post_pound_r,1.35,true),true);
00331
00332
00333
00334 return 0;
00335 }