Public Member Functions | Private Attributes | List of all members
CobPickPlaceActionServer Class Reference

#include <cob_pick_place_action.h>

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 (std::string group_name)
 
void convertGraspKIT (Grasp *current_grasp, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
 
void fillAllGraspsKIT (unsigned int objectClassId, std::string gripper_type, geometry_msgs::PoseStamped object_pose, std::vector< moveit_msgs::Grasp > &grasps)
 
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)
 
void fillSingleGraspKIT (unsigned int objectClassId, std::string gripper_type, 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::MoveGroupInterface 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::TransformBroadcaster tf_broadcaster_
 
tf::TransformListener tf_listener_
 

Detailed Description

Definition at line 45 of file cob_pick_place_action.h.

Constructor & Destructor Documentation

CobPickPlaceActionServer::CobPickPlaceActionServer ( std::string  group_name)
inline

Definition at line 71 of file cob_pick_place_action.h.

CobPickPlaceActionServer::~CobPickPlaceActionServer ( )

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 797 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 412 of file cob_pick_place_action.cpp.

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

Initialize GraspTable

Definition at line 354 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::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 
)

GOAL: -> Get TCPGraspPose for arm_7_link wrt base_footprint

Definition at line 551 of file cob_pick_place_action.cpp.

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

Initialize GraspTable

Definition at line 384 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::initialize ( )

Definition at line 31 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 314 of file cob_pick_place_action.cpp.

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

Definition at line 699 of file cob_pick_place_action.cpp.

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

Get grasps from corresponding GraspTable

Updating the object collision_object

Call Pick

Definition at line 90 of file cob_pick_place_action.cpp.

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

Definition at line 207 of file cob_pick_place_action.cpp.

void CobPickPlaceActionServer::run ( )

Definition at line 84 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 
)

ToDo: get palm-link name from robot!

Definition at line 737 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 56 of file cob_pick_place_action.h.

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

Definition at line 53 of file cob_pick_place_action.h.

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

Definition at line 54 of file cob_pick_place_action.h.

char* CobPickPlaceActionServer::GraspTableIniFile
private

Definition at line 60 of file cob_pick_place_action.h.

moveit::planning_interface::MoveGroupInterface CobPickPlaceActionServer::group
private

Definition at line 58 of file cob_pick_place_action.h.

bool CobPickPlaceActionServer::last_grasp_valid
private

Definition at line 63 of file cob_pick_place_action.h.

std::string CobPickPlaceActionServer::last_object_name
private

Definition at line 64 of file cob_pick_place_action.h.

GraspTable* CobPickPlaceActionServer::m_GraspTable
private

Definition at line 61 of file cob_pick_place_action.h.

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

Definition at line 68 of file cob_pick_place_action.h.

ros::NodeHandle CobPickPlaceActionServer::nh_
private

Definition at line 48 of file cob_pick_place_action.h.

ros::Publisher CobPickPlaceActionServer::pub_ao
private

Definition at line 51 of file cob_pick_place_action.h.

ros::Publisher CobPickPlaceActionServer::pub_co
private

Definition at line 50 of file cob_pick_place_action.h.

tf::TransformBroadcaster CobPickPlaceActionServer::tf_broadcaster_
private

Definition at line 66 of file cob_pick_place_action.h.

tf::TransformListener CobPickPlaceActionServer::tf_listener_
private

Definition at line 65 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 Mon Jun 10 2019 13:10:02