Public Member Functions | Private Attributes
CobPickPlaceActionServer Class Reference

#include <cob_pick_place_action.h>

List of all members.

Public Member Functions

moveit_msgs::GripperTranslation calculateApproachDirection (geometry_msgs::Pose msg_pose_grasp_FOOTPRINT_from_ARM7, geometry_msgs::Pose msg_pose_pre_FOOTPRINT_from_ARM7)
 CobPickPlaceActionServer ()
void convertGraspKIT (Grasp *current_grasp, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
void fillAllGraspsKIT (unsigned int objectClassId, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
void fillGraspsOR (unsigned int objectClassId, unsigned int grasp_id, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
void fillSingleGraspKIT (unsigned int objectClassId, unsigned int grasp_id, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
void initialize ()
void insertObject (std::string object_name, unsigned int object_class, geometry_msgs::PoseStamped object_pose)
trajectory_msgs::JointTrajectory MapHandConfiguration (sensor_msgs::JointState table_config)
void pick_goal_cb (const cob_pick_place_action::CobPickGoalConstPtr &goal)
void place_goal_cb (const cob_pick_place_action::CobPlaceGoalConstPtr &goal)
void run ()
tf::Transform transformPose (tf::Transform transform_O_from_SDH, tf::Transform transform_HEADER_from_OBJECT, std::string object_frame_id)
 ~CobPickPlaceActionServer ()

Private Attributes

boost::scoped_ptr
< actionlib::SimpleActionClient
< cob_grasp_generation::QueryGraspsAction > > 
ac_grasps_or
boost::scoped_ptr
< actionlib::SimpleActionServer
< cob_pick_place_action::CobPickAction > > 
as_pick
boost::scoped_ptr
< actionlib::SimpleActionServer
< cob_pick_place_action::CobPlaceAction > > 
as_place
char * GraspTableIniFile
moveit::planning_interface::MoveGroup group
bool last_grasp_valid
std::string last_object_name
GraspTablem_GraspTable
std::map< unsigned int,
std::string > 
map_classid_to_classname
ros::NodeHandle nh_
ros::Publisher pub_ao
ros::Publisher pub_co
tf::TransformListener tf_listener_

Detailed Description

Definition at line 57 of file cob_pick_place_action.h.


Constructor & Destructor Documentation

Definition at line 82 of file cob_pick_place_action.h.


Member Function Documentation

moveit_msgs::GripperTranslation CobPickPlaceActionServer::calculateApproachDirection ( geometry_msgs::Pose  msg_pose_grasp_FOOTPRINT_from_ARM7,
geometry_msgs::Pose  msg_pose_pre_FOOTPRINT_from_ARM7 
)

Definition at line 761 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::convertGraspKIT ( Grasp current_grasp,
geometry_msgs::PoseStamped  object_pose,
std::vector< moveit_msgs::Grasp > &  grasps 
)

GOAL: -> Get TCPGraspPose for arm_7_link wrt base_footprint

Definition at line 380 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::fillAllGraspsKIT ( unsigned int  objectClassId,
geometry_msgs::PoseStamped  object_pose,
std::vector< moveit_msgs::Grasp > &  grasps 
)

Definition at line 342 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::fillGraspsOR ( unsigned int  objectClassId,
unsigned int  grasp_id,
geometry_msgs::PoseStamped  object_pose,
std::vector< moveit_msgs::Grasp > &  grasps 
)

GOAL: -> Get TCPGraspPose for arm_7_link wrt base_footprint

Definition at line 520 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::fillSingleGraspKIT ( unsigned int  objectClassId,
unsigned int  grasp_id,
geometry_msgs::PoseStamped  object_pose,
std::vector< moveit_msgs::Grasp > &  grasps 
)

Definition at line 363 of file cob_pick_place_action.cpp.

Definition at line 48 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::insertObject ( std::string  object_name,
unsigned int  object_class,
geometry_msgs::PoseStamped  object_pose 
)

Definition at line 309 of file cob_pick_place_action.cpp.

trajectory_msgs::JointTrajectory CobPickPlaceActionServer::MapHandConfiguration ( sensor_msgs::JointState  table_config)

Definition at line 664 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::pick_goal_cb ( const cob_pick_place_action::CobPickGoalConstPtr &  goal)

Updating the object collision_object

Get grasps from corresponding GraspTable

Call Pick

Setting result

Definition at line 113 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::place_goal_cb ( const cob_pick_place_action::CobPlaceGoalConstPtr &  goal)

Setting result

Definition at line 199 of file cob_pick_place_action.cpp.

Definition at line 107 of file cob_pick_place_action.cpp.

tf::Transform CobPickPlaceActionServer::transformPose ( tf::Transform  transform_O_from_SDH,
tf::Transform  transform_HEADER_from_OBJECT,
std::string  object_frame_id 
)

Definition at line 708 of file cob_pick_place_action.cpp.


Member Data Documentation

boost::scoped_ptr<actionlib::SimpleActionClient<cob_grasp_generation::QueryGraspsAction> > CobPickPlaceActionServer::ac_grasps_or [private]

Definition at line 68 of file cob_pick_place_action.h.

boost::scoped_ptr<actionlib::SimpleActionServer<cob_pick_place_action::CobPickAction> > CobPickPlaceActionServer::as_pick [private]

Definition at line 65 of file cob_pick_place_action.h.

boost::scoped_ptr<actionlib::SimpleActionServer<cob_pick_place_action::CobPlaceAction> > CobPickPlaceActionServer::as_place [private]

Definition at line 66 of file cob_pick_place_action.h.

Definition at line 72 of file cob_pick_place_action.h.

Definition at line 70 of file cob_pick_place_action.h.

Definition at line 75 of file cob_pick_place_action.h.

Definition at line 76 of file cob_pick_place_action.h.

Definition at line 73 of file cob_pick_place_action.h.

std::map<unsigned int,std::string> CobPickPlaceActionServer::map_classid_to_classname [private]

Definition at line 79 of file cob_pick_place_action.h.

Definition at line 60 of file cob_pick_place_action.h.

Definition at line 63 of file cob_pick_place_action.h.

Definition at line 62 of file cob_pick_place_action.h.

Definition at line 77 of file cob_pick_place_action.h.


The documentation for this class was generated from the following files:


cob_pick_place_action
Author(s): Felix Messmer
autogenerated on Wed Aug 26 2015 11:01:29