00001 #include <ros/ros.h>
00002 #include <actionlib/client/simple_action_client.h>
00003
00004 #include <move_arm_msgs/MoveArmAction.h>
00005 #include <move_arm_msgs/utils.h>
00006
00007 #include <nav_msgs/Odometry.h>
00008 #include <boost/thread.hpp>
00009
00010 #include "LinearMath/btTransform.h"
00011 #include "LinearMath/btVector3.h"
00012 #include <tf/transform_listener.h>
00013
00014
00015
00016 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
00017 #include <actionlib/client/simple_action_client.h>
00018
00019
00020 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
00021
00022 class Gripper{
00023 private:
00024 GripperClient* gripper_client_;
00025
00026 public:
00027
00028 Gripper(){
00029
00030
00031
00032 gripper_client_ = new GripperClient("r_gripper_controller/gripper_action", true);
00033
00034
00035 while(!gripper_client_->waitForServer(ros::Duration(30.0))){
00036 ROS_INFO("Waiting for the r_gripper_controller/gripper_action action server to come up");
00037 }
00038 }
00039
00040 ~Gripper(){
00041 delete gripper_client_;
00042 }
00043
00044
00045 void open(){
00046 pr2_controllers_msgs::Pr2GripperCommandGoal open;
00047 open.command.position = 0.08;
00048 open.command.max_effort = -1.0;
00049
00050 ROS_INFO("Sending open goal");
00051 gripper_client_->sendGoal(open);
00052 gripper_client_->waitForResult();
00053 if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00054 ROS_INFO("The gripper opened!");
00055 else
00056 ROS_INFO("The gripper failed to open.");
00057 }
00058
00059
00060 void close(){
00061 pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
00062 squeeze.command.position = 0.0;
00063 squeeze.command.max_effort = 50.0;
00064
00065
00066
00067
00068
00069 ROS_INFO("Sending squeeze goal, wait for 5 seconds, check for stall, then continue");
00070 if(gripper_client_->sendGoalAndWait(squeeze,ros::Duration(5.0)) == actionlib::SimpleClientGoalState::SUCCEEDED)
00071 ROS_INFO("The gripper closed!");
00072 else
00073 {
00074 gripper_client_->sendGoal(squeeze);
00075 if (gripper_client_->getResult()->stalled)
00076 ROS_INFO("The gripper failed to close and is stalled, possibly holding an object.");
00077 else
00078 ROS_INFO("The gripper failed to close and is not stalled, something is wrong.");
00079 }
00080 }
00081 };
00082
00083 class objectPose
00084 {
00085 public:
00086 bool got_pose_;
00087 nav_msgs::Odometry pose_;
00088 ros::Subscriber sub_;
00089
00090 objectPose(ros::NodeHandle& nh,std::string topic)
00091 {
00092 this->got_pose_ = false;
00093 this->sub_ = nh.subscribe(topic, 1, &objectPose::poseCallback, this);
00094 };
00095 void poseCallback(const nav_msgs::OdometryConstPtr& pose)
00096 {
00097 this->pose_ = *pose;
00098 this->got_pose_ = true;
00099 };
00100 };
00101
00102
00103 int main(int argc, char **argv){
00104 ros::init (argc, argv, "move_arm_pose_goal_test");
00105 ros::NodeHandle nh;
00106
00107 ros::MultiThreadedSpinner s(4);
00108 boost::thread* ros_spinner = new boost::thread(boost::bind(&ros::spin,s));
00109
00110
00111
00112
00113
00114
00115 Gripper gripper;
00116 gripper.open();
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126 std::string target_frame = "r_gripper_tool_frame";
00127 std::string command_link = "r_wrist_roll_link";
00128 ROS_INFO("waiting for transform from %s to %s",command_link.c_str(),target_frame.c_str());
00129 tf::TransformListener listener;
00130 tf::StampedTransform target_to_command_link;
00131 listener.waitForTransform(target_frame,command_link,ros::Time(),ros::Duration(100.0));
00132 listener.lookupTransform(target_frame,command_link,ros::Time(0),target_to_command_link);
00133
00134
00135
00136
00137
00138
00139
00140 actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> move_arm("move_right_arm",true);
00141 ROS_INFO("Connecting to move arm server");
00142 move_arm.waitForServer();
00143
00144
00145
00146
00147
00148
00149
00150
00151 objectPose pcb(nh,"/plug/plug_pose_ground_truth");
00152
00153 ROS_INFO("waiting for /plug/plug_pose_ground_truth from sim");
00154 while (!pcb.got_pose_)
00155 {
00156 ROS_DEBUG("checking for plug pose (%d)", pcb.got_pose_ );
00157 ros::Duration(1.0).sleep();
00158 }
00159
00160
00161 std::string plug_reference_frame = pcb.pose_.header.frame_id;
00162
00163 btQuaternion target_rot_90yaw; target_rot_90yaw.setEuler(0,0,M_PI/2);
00164
00165
00166 btTransform plug_transform(btQuaternion(pcb.pose_.pose.pose.orientation.x,
00167 pcb.pose_.pose.pose.orientation.y,
00168 pcb.pose_.pose.pose.orientation.z,
00169 pcb.pose_.pose.pose.orientation.w)*target_rot_90yaw,
00170 btVector3(pcb.pose_.pose.pose.position.x,
00171 pcb.pose_.pose.pose.position.y,
00172 pcb.pose_.pose.pose.position.z));
00173 plug_transform = plug_transform*(btTransform)target_to_command_link;
00174
00175 move_arm_msgs::MoveArmGoal goalA;
00176
00177 goalA.group_name = "right_arm";
00178 goalA.num_planning_attempts = 1;
00179 goalA.planner_id = std::string("");
00180 goalA.planner_service_name = std::string("ompl_planning/plan_kinematic_path");
00181 goalA.allowed_planning_time = 5.0;
00182
00183 motion_planning_msgs::SimplePoseConstraint desired_poseA;
00184
00185 desired_poseA.header = pcb.pose_.header;
00186 desired_poseA.link_name = command_link;
00187
00188 desired_poseA.pose.position.x = plug_transform.getOrigin().x();
00189 desired_poseA.pose.position.y = plug_transform.getOrigin().y() - 0.05;
00190 desired_poseA.pose.position.z = plug_transform.getOrigin().z();
00191 desired_poseA.pose.orientation.x = plug_transform.getRotation().x();
00192 desired_poseA.pose.orientation.y = plug_transform.getRotation().y();
00193 desired_poseA.pose.orientation.z = plug_transform.getRotation().z();
00194 desired_poseA.pose.orientation.w = plug_transform.getRotation().w();
00195
00196
00197 desired_poseA.absolute_position_tolerance.x = 0.02;
00198 desired_poseA.absolute_position_tolerance.y = 0.02;
00199 desired_poseA.absolute_position_tolerance.z = 0.02;
00200
00201 desired_poseA.absolute_roll_tolerance = 0.04;
00202 desired_poseA.absolute_pitch_tolerance = 0.04;
00203 desired_poseA.absolute_yaw_tolerance = 0.04;
00204
00205 ROS_INFO("sending approach pose goal to server");
00206 move_arm_msgs::addGoalConstraintToMoveArmGoal(desired_poseA,goalA);
00207
00208
00209
00210 if (nh.ok())
00211 {
00212 bool finished_within_time = false;
00213 int retries = 0;
00214 int max_retries = 10;
00215 move_arm.sendGoal(goalA);
00216 finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00217
00218 while (!finished_within_time && retries <= max_retries)
00219 {
00220 retries++;
00221 move_arm.sendGoal(goalA);
00222 finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00223 }
00224
00225 if (!finished_within_time)
00226 {
00227 ROS_INFO("Timed out achieving goal A");
00228 move_arm.cancelGoal();
00229 }
00230 else
00231 {
00232 actionlib::SimpleClientGoalState state = move_arm.getState();
00233 bool success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00234 if(success)
00235 ROS_INFO("Action finished: %s",state.toString().c_str());
00236 else
00237 ROS_INFO("Action failed: %s",state.toString().c_str());
00238 }
00239 }
00240
00241
00242
00243
00244
00245
00246 move_arm_msgs::MoveArmGoal goalB;
00247
00248 goalB.group_name = "right_arm";
00249 goalB.num_planning_attempts = 1;
00250 goalB.planner_id = std::string("");
00251 goalB.planner_service_name = std::string("ompl_planning/plan_kinematic_path");
00252 goalB.allowed_planning_time = 5.0;
00253
00254 motion_planning_msgs::SimplePoseConstraint desired_poseB;
00255
00256 desired_poseB.header = pcb.pose_.header;
00257 desired_poseB.link_name = command_link;
00258
00259 desired_poseB.pose.position.x = plug_transform.getOrigin().x();
00260 desired_poseB.pose.position.y = plug_transform.getOrigin().y();
00261 desired_poseB.pose.position.z = plug_transform.getOrigin().z();
00262 desired_poseB.pose.orientation.x = plug_transform.getRotation().x();
00263 desired_poseB.pose.orientation.y = plug_transform.getRotation().y();
00264 desired_poseB.pose.orientation.z = plug_transform.getRotation().z();
00265 desired_poseB.pose.orientation.w = plug_transform.getRotation().w();
00266
00267
00268 desired_poseB.absolute_position_tolerance.x = 0.02;
00269 desired_poseB.absolute_position_tolerance.y = 0.02;
00270 desired_poseB.absolute_position_tolerance.z = 0.02;
00271
00272 desired_poseB.absolute_roll_tolerance = 0.04;
00273 desired_poseB.absolute_pitch_tolerance = 0.04;
00274 desired_poseB.absolute_yaw_tolerance = 0.04;
00275
00276 ROS_INFO("sending plug pose goal to server");
00277 move_arm_msgs::addGoalConstraintToMoveArmGoal(desired_poseB,goalB);
00278
00279
00280
00281 if (nh.ok())
00282 {
00283 bool finished_within_time = false;
00284 int retries = 0;
00285 int max_retries = 10;
00286 move_arm.sendGoal(goalB);
00287 finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00288 while (!finished_within_time && retries <= max_retries)
00289 {
00290 retries++;
00291 move_arm.sendGoal(goalB);
00292 finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00293 }
00294
00295 if (!finished_within_time)
00296 {
00297 move_arm.cancelGoal();
00298 ROS_INFO("Timed out achieving goal B");
00299 }
00300 else
00301 {
00302 actionlib::SimpleClientGoalState state = move_arm.getState();
00303 bool success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00304 if(success)
00305 ROS_INFO("Action finished: %s",state.toString().c_str());
00306 else
00307 ROS_INFO("Action failed: %s",state.toString().c_str());
00308 }
00309 }
00310
00311
00312
00313
00314
00315
00316 ROS_INFO("closing gripper around object");
00317 gripper.close();
00318
00319
00320
00321
00322
00323
00324
00325 objectPose ocb(nh,"/outlet/outlet_pose_ground_truth");
00326 ROS_INFO("waiting for /outlet/outlet_pose_ground_truth from sim");
00327 while (!ocb.got_pose_)
00328 {
00329 ROS_DEBUG("checking for outlet pose (%d)", ocb.got_pose_ );
00330 ros::Duration(1.0).sleep();
00331 }
00332
00333 std::string outlet_reference_frame = ocb.pose_.header.frame_id;
00334
00335
00336 btTransform outlet_transform(btQuaternion(ocb.pose_.pose.pose.orientation.x,
00337 ocb.pose_.pose.pose.orientation.y,
00338 ocb.pose_.pose.pose.orientation.z,
00339 ocb.pose_.pose.pose.orientation.w),
00340 btVector3(ocb.pose_.pose.pose.position.x,
00341 ocb.pose_.pose.pose.position.y,
00342 ocb.pose_.pose.pose.position.z));
00343 outlet_transform = outlet_transform*(btTransform)target_to_command_link;
00344
00345 move_arm_msgs::MoveArmGoal goalC;
00346
00347 goalC.group_name = "right_arm";
00348 goalC.num_planning_attempts = 100;
00349 goalC.planner_id = std::string("");
00350 goalC.planner_service_name = std::string("ompl_planning/plan_kinematic_path");
00351 goalC.allowed_planning_time = 5.0;
00352
00353 motion_planning_msgs::SimplePoseConstraint desired_poseC;
00354
00355 desired_poseC.header = ocb.pose_.header;
00356 desired_poseC.link_name = command_link;
00357 desired_poseC.pose.position.x = outlet_transform.getOrigin().x()-0.10;
00358 desired_poseC.pose.position.y = outlet_transform.getOrigin().y();
00359 desired_poseC.pose.position.z = outlet_transform.getOrigin().z();
00360 desired_poseC.pose.orientation.x = outlet_transform.getRotation().x();
00361 desired_poseC.pose.orientation.y = outlet_transform.getRotation().y();
00362 desired_poseC.pose.orientation.z = outlet_transform.getRotation().z();
00363 desired_poseC.pose.orientation.w = outlet_transform.getRotation().w();
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377 desired_poseC.absolute_position_tolerance.x = 0.02;
00378 desired_poseC.absolute_position_tolerance.y = 0.02;
00379 desired_poseC.absolute_position_tolerance.z = 0.02;
00380
00381 desired_poseC.absolute_roll_tolerance = 0.04;
00382 desired_poseC.absolute_pitch_tolerance = 0.04;
00383 desired_poseC.absolute_yaw_tolerance = 0.04;
00384
00385 ROS_INFO("sending outlet pose goal to server");
00386 move_arm_msgs::addGoalConstraintToMoveArmGoal(desired_poseC,goalC);
00387
00388
00389
00390 if (nh.ok())
00391 {
00392 bool finished_within_time = false;
00393 int retries = 0;
00394 int max_retries = 10;
00395 move_arm.sendGoal(goalC);
00396 finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00397 while (!finished_within_time && retries <= max_retries)
00398 {
00399 retries++;
00400 move_arm.sendGoal(goalC);
00401 finished_within_time = move_arm.waitForResult(ros::Duration(200.0));
00402 }
00403 if (!finished_within_time)
00404 {
00405 move_arm.cancelGoal();
00406 ROS_INFO("Timed out achieving goal C");
00407 }
00408 else
00409 {
00410 actionlib::SimpleClientGoalState state = move_arm.getState();
00411 bool success = (state == actionlib::SimpleClientGoalState::SUCCEEDED);
00412 if(success)
00413 ROS_INFO("Action finished: %s",state.toString().c_str());
00414 else
00415 ROS_INFO("Action failed: %s",state.toString().c_str());
00416 }
00417 }
00418
00419
00420
00421
00422 ros::shutdown();
00423 ros_spinner->join();
00424 }