cob_pick_place_action.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_PICK_ACTION_H
19 #define COB_PICK_ACTION_H
20 
21 #include <iostream>
22 #include <fstream>
23 #include <ros/ros.h>
24 #include <ros/package.h>
28 
29 #include <tf/tf.h>
31 #include <tf/transform_datatypes.h>
32 
36 #include <moveit_msgs/Grasp.h>
37 
38 #include <cob_pick_place_action/CobPickAction.h>
39 #include <cob_pick_place_action/CobPlaceAction.h>
40 #include <cob_grasp_generation/QueryGraspsAction.h>
41 #include <GraspTable.h>
42 
43 
44 
46 {
47 private:
49 
50  ros::Publisher pub_co; //publisher for collision_objects
51  ros::Publisher pub_ao; //publisher for attached_collision_objects
52 
53  boost::scoped_ptr<actionlib::SimpleActionServer<cob_pick_place_action::CobPickAction> > as_pick;
54  boost::scoped_ptr<actionlib::SimpleActionServer<cob_pick_place_action::CobPlaceAction> > as_place;
55 
56  boost::scoped_ptr<actionlib::SimpleActionClient<cob_grasp_generation::QueryGraspsAction> > ac_grasps_or;
57 
59 
62 
64  std::string last_object_name;
67 
68  std::map<unsigned int,std::string> map_classid_to_classname;
69 
70 public:
71  CobPickPlaceActionServer(std::string group_name) : group(group_name) {}
73 
74  void initialize();
75  void run();
76 
77  void pick_goal_cb(const cob_pick_place_action::CobPickGoalConstPtr &goal);
78  void place_goal_cb(const cob_pick_place_action::CobPlaceGoalConstPtr &goal);
79 
80  void insertObject(std::string object_name, unsigned int object_class, geometry_msgs::PoseStamped object_pose);
81 
82  void fillAllGraspsKIT(unsigned int objectClassId, std::string gripper_type, geometry_msgs::PoseStamped object_pose, std::vector<moveit_msgs::Grasp> &grasps);
83  void fillSingleGraspKIT(unsigned int objectClassId, std::string gripper_type, unsigned int grasp_id, geometry_msgs::PoseStamped object_pose, std::vector<moveit_msgs::Grasp> &grasps);
84  void convertGraspKIT(Grasp* current_grasp, geometry_msgs::PoseStamped object_pose, std::vector<moveit_msgs::Grasp> &grasps);
85 
86  void fillGraspsOR(unsigned int objectClassId, std::string gripper_type, std::string gripper_side, unsigned int grasp_id, geometry_msgs::PoseStamped object_pose, std::vector<moveit_msgs::Grasp> &grasps);
87 
88  trajectory_msgs::JointTrajectory MapHandConfiguration(sensor_msgs::JointState table_config);
89  tf::Transform transformPose(tf::Transform transform_O_from_SDH, tf::Transform transform_HEADER_from_OBJECT, std::string object_frame_id);
90  moveit_msgs::GripperTranslation calculateApproachDirection(geometry_msgs::Pose msg_pose_grasp_FOOTPRINT_from_ARM7, geometry_msgs::Pose msg_pose_pre_FOOTPRINT_from_ARM7);
91 
92 };
93 #endif
94 
95 
string object_name
ADDING OBJECT.
moveit_msgs::GripperTranslation calculateApproachDirection(geometry_msgs::Pose msg_pose_grasp_FOOTPRINT_from_ARM7, geometry_msgs::Pose msg_pose_pre_FOOTPRINT_from_ARM7)
boost::scoped_ptr< actionlib::SimpleActionServer< cob_pick_place_action::CobPlaceAction > > as_place
void fillGraspsOR(unsigned int objectClassId, std::string gripper_type, std::string gripper_side, unsigned int grasp_id, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
tf::TransformBroadcaster tf_broadcaster_
CobPickPlaceActionServer(std::string group_name)
boost::scoped_ptr< actionlib::SimpleActionServer< cob_pick_place_action::CobPickAction > > as_pick
boost::scoped_ptr< actionlib::SimpleActionClient< cob_grasp_generation::QueryGraspsAction > > ac_grasps_or
void insertObject(std::string object_name, unsigned int object_class, geometry_msgs::PoseStamped object_pose)
moveit::planning_interface::MoveGroupInterface group
void fillSingleGraspKIT(unsigned int objectClassId, std::string gripper_type, unsigned int grasp_id, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
tf::Transform transformPose(tf::Transform transform_O_from_SDH, tf::Transform transform_HEADER_from_OBJECT, std::string object_frame_id)
void place_goal_cb(const cob_pick_place_action::CobPlaceGoalConstPtr &goal)
trajectory_msgs::JointTrajectory MapHandConfiguration(sensor_msgs::JointState table_config)
tf::TransformListener tf_listener_
void pick_goal_cb(const cob_pick_place_action::CobPickGoalConstPtr &goal)
std::map< unsigned int, std::string > map_classid_to_classname
void fillAllGraspsKIT(unsigned int objectClassId, std::string gripper_type, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
void convertGraspKIT(Grasp *current_grasp, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)


cob_pick_place_action
Author(s): Felix Messmer
autogenerated on Mon Jun 10 2019 13:10:02