18 #ifndef COB_PICK_ACTION_H 19 #define COB_PICK_ACTION_H 36 #include <moveit_msgs/Grasp.h> 38 #include <cob_pick_place_action/CobPickAction.h> 39 #include <cob_pick_place_action/CobPlaceAction.h> 40 #include <cob_grasp_generation/QueryGraspsAction.h> 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;
56 boost::scoped_ptr<actionlib::SimpleActionClient<cob_grasp_generation::QueryGraspsAction> >
ac_grasps_or;
77 void pick_goal_cb(
const cob_pick_place_action::CobPickGoalConstPtr &goal);
78 void place_goal_cb(
const cob_pick_place_action::CobPlaceGoalConstPtr &goal);
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);
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);
90 moveit_msgs::GripperTranslation
calculateApproachDirection(geometry_msgs::Pose msg_pose_grasp_FOOTPRINT_from_ARM7, geometry_msgs::Pose msg_pose_pre_FOOTPRINT_from_ARM7);
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
~CobPickPlaceActionServer()
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)
std::string last_object_name
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)
GraspTable * m_GraspTable
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)