00001 00010 #ifndef SR_MOVE_ARM_SIMPLE_ACTION_H 00011 #define SR_MOVE_ARM_SIMPLE_ACTION_H 00012 00013 #include <ros/ros.h> 00014 #include <boost/smart_ptr.hpp> 00015 #include <sr_robot_msgs/is_hand_occupied.h> 00016 #include <sr_hand/hand_commander.hpp> 00017 00018 #include <actionlib/server/simple_action_server.h> 00019 #include <object_manipulation_msgs/GraspHandPostureExecutionAction.h> 00020 #include <object_manipulation_msgs/GraspStatus.h> 00021 #include <object_manipulation_msgs/ManipulationResult.h> 00022 00023 #include <trajectory_msgs/JointTrajectory.h> 00024 00025 using namespace ros; 00026 00027 namespace shadowrobot 00028 { 00029 class SrHandPostureExecutionSimpleAction 00030 { 00031 public: 00032 SrHandPostureExecutionSimpleAction(); 00033 ~SrHandPostureExecutionSimpleAction(); 00034 00035 protected: 00036 NodeHandle nh, nh_tilde; 00037 Publisher pub; 00038 void execute(const object_manipulation_msgs::GraspHandPostureExecutionGoalConstPtr& goal); 00039 bool getStatusCallback(object_manipulation_msgs::GraspStatus::Request &request, 00040 object_manipulation_msgs::GraspStatus::Response &response); 00041 00042 boost::shared_ptr<actionlib::SimpleActionServer<object_manipulation_msgs::GraspHandPostureExecutionAction> > action_server; 00043 00044 boost::shared_ptr<shadowrobot::HandCommander> shadowhand_ros_lib; 00045 ServiceServer get_status_server; 00046 ServiceClient is_hand_occupied_client; 00047 std::vector<sr_robot_msgs::joint> joint_vector; 00048 00049 bool hand_occupied; 00050 };//end class 00051 }//end workspace 00052 00053 /* For the emacs weenies in the crowd. 00054 Local Variables: 00055 c-basic-offset: 2 00056 End: 00057 */ 00058 00059 #endif //SR_MOVE_ARM_SIMPLE_ACTION_H