Go to the documentation of this file.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 #include <ros/ros.h>
00032 #include <tf/tf.h>
00033
00034 #include <actionlib/server/simple_action_server.h>
00035 #include <turtlebot_block_manipulation/PickAndPlaceAction.h>
00036
00037 #include <actionlib/client/simple_action_client.h>
00038 #include <simple_arm_server/MoveArmAction.h>
00039
00040 #include <geometry_msgs/PoseArray.h>
00041
00042 namespace turtlebot_block_manipulation
00043 {
00044
00045 class PickAndPlaceServer
00046 {
00047 private:
00048
00049 ros::NodeHandle nh_;
00050 actionlib::SimpleActionServer<turtlebot_block_manipulation::PickAndPlaceAction> as_;
00051 std::string action_name_;
00052
00053 turtlebot_block_manipulation::PickAndPlaceFeedback feedback_;
00054 turtlebot_block_manipulation::PickAndPlaceResult result_;
00055 turtlebot_block_manipulation::PickAndPlaceGoalConstPtr goal_;
00056
00057 actionlib::SimpleActionClient<simple_arm_server::MoveArmAction> client_;
00058
00059 ros::Subscriber pick_and_place_sub_;
00060
00061
00062 std::string arm_link;
00063 double gripper_open;
00064 double gripper_closed;
00065 double z_up;
00066 public:
00067 PickAndPlaceServer(const std::string name) :
00068 nh_("~"), as_(name, false), action_name_(name), client_("/move_arm", true)
00069 {
00070
00071
00072 as_.registerGoalCallback(boost::bind(&PickAndPlaceServer::goalCB, this));
00073 as_.registerPreemptCallback(boost::bind(&PickAndPlaceServer::preemptCB, this));
00074
00075 as_.start();
00076 }
00077
00078 void goalCB()
00079 {
00080 ROS_INFO("[pick and place] Received goal!");
00081 goal_ = as_.acceptNewGoal();
00082 arm_link = goal_->frame;
00083 gripper_open = goal_->gripper_open;
00084 gripper_closed = goal_->gripper_closed;
00085 z_up = goal_->z_up;
00086
00087 if (goal_->topic.length() < 1)
00088 pickAndPlace(goal_->pickup_pose, goal_->place_pose);
00089 else
00090 pick_and_place_sub_ = nh_.subscribe(goal_->topic, 1, &PickAndPlaceServer::sendGoalFromTopic, this);
00091 }
00092
00093 void sendGoalFromTopic(const geometry_msgs::PoseArrayConstPtr& msg)
00094 {
00095 ROS_INFO("[pick and place] Got goal from topic! %s", goal_->topic.c_str());
00096 pickAndPlace(msg->poses[0], msg->poses[1]);
00097 pick_and_place_sub_.shutdown();
00098 }
00099
00100 void preemptCB()
00101 {
00102 ROS_INFO("%s: Preempted", action_name_.c_str());
00103
00104 as_.setPreempted();
00105 }
00106
00107 void pickAndPlace(const geometry_msgs::Pose& start_pose, const geometry_msgs::Pose& end_pose)
00108 {
00109 ROS_INFO("[pick and place] Picking. Also placing.");
00110
00111 simple_arm_server::MoveArmGoal goal;
00112 simple_arm_server::ArmAction action;
00113 simple_arm_server::ArmAction grip;
00114
00115
00116 grip.type = simple_arm_server::ArmAction::MOVE_GRIPPER;
00117 grip.move_time.sec = 1.0;
00118 grip.command = gripper_open;
00119 goal.motions.push_back(grip);
00120
00121
00122 tf::Quaternion temp;
00123 temp.setRPY(0,1.57,0);
00124 action.goal.orientation.x = temp.getX();
00125 action.goal.orientation.y = temp.getY();
00126 action.goal.orientation.z = temp.getZ();
00127 action.goal.orientation.w = temp.getW();
00128
00129
00130 action.goal.position.x = start_pose.position.x;
00131 action.goal.position.y = start_pose.position.y;
00132 action.goal.position.z = z_up;
00133 action.move_time.sec = 0.25;
00134 goal.motions.push_back(action);
00135
00136
00137 action.goal.position.z = start_pose.position.z;
00138 action.move_time.sec = 1.5;
00139 goal.motions.push_back(action);
00140
00141
00142 grip.type = simple_arm_server::ArmAction::MOVE_GRIPPER;
00143 grip.command = gripper_closed;
00144 grip.move_time.sec = 1.0;
00145 goal.motions.push_back(grip);
00146
00147
00148 action.goal.position.z = z_up;
00149 action.move_time.sec = 1.0;
00150 goal.motions.push_back(action);
00151
00152
00153 action.goal.position.x = end_pose.position.x;
00154 action.goal.position.y = end_pose.position.y;
00155 action.goal.position.z = z_up;
00156 action.move_time.sec = 1.0;
00157 goal.motions.push_back(action);
00158
00159
00160 action.goal.position.z = end_pose.position.z;
00161 action.move_time.sec = 1.5;
00162 goal.motions.push_back(action);
00163
00164
00165 grip.command = gripper_open;
00166 goal.motions.push_back(grip);
00167
00168
00169 action.goal.position.z = z_up;
00170 action.move_time.sec = 1.0;
00171 goal.motions.push_back(action);
00172
00173 goal.header.frame_id = arm_link;
00174 client_.sendGoal(goal);
00175 ROS_INFO("[pick and place] Sent goal. Waiting.");
00176 client_.waitForResult(ros::Duration(30.0));
00177 ROS_INFO("[pick and place] Received result.");
00178 if (client_.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00179 as_.setSucceeded(result_);
00180 else
00181 {
00182 ROS_INFO("Actual state: %s", client_.getState().toString().c_str());
00183 as_.setAborted(result_);
00184 }
00185 }
00186 };
00187
00188 };
00189
00190
00191 int main(int argc, char** argv)
00192 {
00193 ros::init(argc, argv, "pick_and_place_action_server");
00194
00195 turtlebot_block_manipulation::PickAndPlaceServer server("pick_and_place");
00196 ros::spin();
00197
00198 return 0;
00199 }
00200