#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::MoveGroup | group |
bool | last_grasp_valid |
std::string | last_object_name |
GraspTable * | m_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_ |
Definition at line 46 of file cob_pick_place_action.h.
CobPickPlaceActionServer::CobPickPlaceActionServer | ( | std::string | group_name | ) | [inline] |
Definition at line 72 of file cob_pick_place_action.h.
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 792 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 407 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 349 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 546 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 379 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 309 of file cob_pick_place_action.cpp.
trajectory_msgs::JointTrajectory CobPickPlaceActionServer::MapHandConfiguration | ( | sensor_msgs::JointState | table_config | ) |
Definition at line 694 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 | ) |
Setting result
Definition at line 205 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 732 of file cob_pick_place_action.cpp.
boost::scoped_ptr<actionlib::SimpleActionClient<cob_grasp_generation::QueryGraspsAction> > CobPickPlaceActionServer::ac_grasps_or [private] |
Definition at line 57 of file cob_pick_place_action.h.
boost::scoped_ptr<actionlib::SimpleActionServer<cob_pick_place_action::CobPickAction> > CobPickPlaceActionServer::as_pick [private] |
Definition at line 54 of file cob_pick_place_action.h.
boost::scoped_ptr<actionlib::SimpleActionServer<cob_pick_place_action::CobPlaceAction> > CobPickPlaceActionServer::as_place [private] |
Definition at line 55 of file cob_pick_place_action.h.
char* CobPickPlaceActionServer::GraspTableIniFile [private] |
Definition at line 61 of file cob_pick_place_action.h.
Definition at line 59 of file cob_pick_place_action.h.
bool CobPickPlaceActionServer::last_grasp_valid [private] |
Definition at line 64 of file cob_pick_place_action.h.
std::string CobPickPlaceActionServer::last_object_name [private] |
Definition at line 65 of file cob_pick_place_action.h.
GraspTable* CobPickPlaceActionServer::m_GraspTable [private] |
Definition at line 62 of file cob_pick_place_action.h.
std::map<unsigned int,std::string> CobPickPlaceActionServer::map_classid_to_classname [private] |
Definition at line 69 of file cob_pick_place_action.h.
ros::NodeHandle CobPickPlaceActionServer::nh_ [private] |
Definition at line 49 of file cob_pick_place_action.h.
Definition at line 52 of file cob_pick_place_action.h.
Definition at line 51 of file cob_pick_place_action.h.
Definition at line 67 of file cob_pick_place_action.h.
Definition at line 66 of file cob_pick_place_action.h.