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
00032
00033 #include <ros/ros.h>
00034 #include <actionlib/server/action_server.h>
00035 #include <object_manipulation_msgs/GraspHandPostureExecutionAction.h>
00036 #include "object_manipulation_msgs/GraspHandPostureExecutionGoal.h"
00037
00038 using namespace object_manipulation_msgs;
00039 using namespace actionlib;
00040
00041 class GraspExecutionAction
00042 {
00043 private:
00044 typedef ActionServer<GraspHandPostureExecutionAction> GEAS;
00045 typedef GEAS::GoalHandle GoalHandle;
00046 public:
00047 GraspExecutionAction(ros::NodeHandle &n) :
00048 node_(n),
00049 action_server_(node_, "grasp_execution_action",
00050 boost::bind(&GraspExecutionAction::goalCB, this, _1),
00051 boost::bind(&GraspExecutionAction::cancelCB, this, _1),
00052 false)
00053 {
00054 ros::NodeHandle pn("~");
00055 action_server_.start();
00056 ROS_INFO_STREAM("Grasp execution action node started");
00057 }
00058
00059 ~GraspExecutionAction()
00060 {
00061 }
00062
00063 private:
00064
00065
00066 void goalCB(GoalHandle gh)
00067 {
00068 std::string nodeName = ros::this_node::getName();
00069
00070 ROS_INFO("%s",(nodeName + ": Received grasping goal").c_str());
00071
00072 switch(gh.getGoal()->goal)
00073 {
00074 case GraspHandPostureExecutionGoal::PRE_GRASP:
00075 gh.setAccepted();
00076
00077 ROS_INFO("%s",(nodeName + ": Pre-grasp command accepted").c_str());
00078 gh.setSucceeded();
00079 break;
00080
00081 case GraspHandPostureExecutionGoal::GRASP:
00082 gh.setAccepted();
00083 ROS_INFO("%s",(nodeName + ": Executing a gripper grasp").c_str());
00084
00085
00086 ros::Duration(1.0f).sleep();
00087 gh.setSucceeded();
00088 break;
00089
00090 case GraspHandPostureExecutionGoal::RELEASE:
00091 gh.setAccepted();
00092 ROS_INFO("%s",(nodeName + ": Executing a gripper release").c_str());
00093
00094
00095 ros::Duration(1.0f).sleep();
00096 gh.setSucceeded();
00097 break;
00098
00099 default:
00100
00101 ROS_INFO("%s",(nodeName + ": Unidentified grasp request, rejecting goal").c_str());
00102 gh.setSucceeded();
00103
00104 break;
00105 }
00106
00107 }
00108
00109 void cancelCB(GoalHandle gh)
00110 {
00111 std::string nodeName = ros::this_node::getName();
00112 ROS_INFO("%s",(nodeName + ": Canceling current grasp action").c_str());
00113
00114 gh.setCanceled();
00115 ROS_INFO("%s",(nodeName + ": Current grasp action has been canceled").c_str());
00116 }
00117
00118 ros::NodeHandle node_;
00119 GEAS action_server_;
00120
00121 };
00122
00123 int main(int argc, char** argv)
00124 {
00125 ros::init(argc, argv, "grasp_execution_action_node");
00126 ros::NodeHandle node;
00127 GraspExecutionAction ge(node);
00128 ros::spin();
00129 return 0;
00130 }
00131
00132
00133
00134