$search
00001 /* 00002 * UOS-ROS packages - Robot Operating System code by the University of Osnabrück 00003 * Copyright (C) 2010 University of Osnabrück 00004 * 00005 * This program is free software; you can redistribute it and/or 00006 * modify it under the terms of the GNU General Public License 00007 * as published by the Free Software Foundation; either version 2 00008 * of the License, or (at your option) any later version. 00009 * 00010 * This program is distributed in the hope that it will be useful, 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00013 * GNU General Public License for more details. 00014 * 00015 * You should have received a copy of the GNU General Public License 00016 * along with this program; if not, write to the Free Software 00017 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 00018 * 00019 * pick_and_place_demo.h 00020 * 00021 * Created on: 31.01.2011 00022 * Author: Martin Günther <mguenthe@uos.de> 00023 */ 00024 00025 #ifndef PICK_AND_PLACE_DEMO_H_ 00026 #define PICK_AND_PLACE_DEMO_H_ 00027 00028 #include <ros/ros.h> 00029 #include <actionlib/client/simple_action_client.h> 00030 00031 #include <move_arm_msgs/MoveArmAction.h> 00032 00033 #include <object_manipulation_msgs/GraspHandPostureExecutionAction.h> 00034 #include <object_manipulation_msgs/GraspStatus.h> 00035 00036 #include <collision_environment_msgs/MakeStaticCollisionMapAction.h> 00037 00038 typedef object_manipulation_msgs::GraspHandPostureExecutionGoal GHPEG; 00039 00040 namespace katana_openloop_grasping 00041 { 00042 00043 static const size_t NUM_JOINTS = 5; 00044 00045 static const double GRIPPER_OPEN_ANGLE = 0.30; 00046 static const double GRIPPER_CLOSED_ANGLE = -0.44; 00047 00048 class PickAndPlaceDemo 00049 { 00050 public: 00051 PickAndPlaceDemo(); 00052 virtual ~PickAndPlaceDemo(); 00053 00054 void loop(); 00055 00056 private: 00057 ros::NodeHandle nh_; 00058 actionlib::SimpleActionClient<move_arm_msgs::MoveArmAction> move_arm_; 00059 actionlib::SimpleActionClient<object_manipulation_msgs::GraspHandPostureExecutionAction> gripper_; 00060 actionlib::SimpleActionClient<collision_environment_msgs::MakeStaticCollisionMapAction> make_static_collision_map_; 00061 ros::ServiceClient grasp_status_client_; 00062 00063 bool move_to_joint_goal(std::vector<motion_planning_msgs::JointConstraint> joint_constraints); 00064 bool send_gripper_action(int32_t goal_type); 00065 bool make_static_collision_map(); 00066 bool query_grasp_status(); 00067 00068 }; 00069 00070 } 00071 00072 #endif /* PICK_AND_PLACE_DEMO_H_ */