grasp_action_service_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *       * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *       * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *       * Neither the name of the Southwest Research Institute, nor the names
00016  *       of its contributors may be used to endorse or promote products derived
00017  *       from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
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                         //gh.getGoal()->grasp
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                         // wait
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                         // wait
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                         //gh.setRejected();
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     //gh.setAccepted();
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 


object_manipulation_tools
Author(s): Jnicho
autogenerated on Mon Oct 6 2014 00:56:17