Public Member Functions | |
void | pick (const calvin_msgs::PickAndStoreGoalConstPtr &goal) |
PickServer (std::string name) | |
bool | place (std::string id) |
~PickServer () | |
Protected Member Functions | |
moveit_msgs::Grasp | build_grasp (tf::Transform t, const double close_width) |
std::vector< moveit_msgs::Grasp > | generate_grasps (double x, double y, double z, const double width) |
void | publish_grasps_as_markerarray (std::vector< moveit_msgs::Grasp > grasps) |
Protected Attributes | |
actionlib::SimpleActionServer < calvin_msgs::PickAndStoreAction > * | actionserver |
ros::Publisher | grasps_marker |
moveit::planning_interface::MoveGroup * | group |
ros::NodeHandle | nh |
Definition at line 14 of file pick_server.cpp.
PickServer::PickServer | ( | std::string | name | ) | [inline] |
Definition at line 172 of file pick_server.cpp.
PickServer::~PickServer | ( | ) | [inline] |
Definition at line 179 of file pick_server.cpp.
moveit_msgs::Grasp PickServer::build_grasp | ( | tf::Transform | t, |
const double | close_width | ||
) | [inline, protected] |
Definition at line 46 of file pick_server.cpp.
std::vector<moveit_msgs::Grasp> PickServer::generate_grasps | ( | double | x, |
double | y, | ||
double | z, | ||
const double | width | ||
) | [inline, protected] |
x, y, z: center of grasp point (the point that should be between the finger tips of the gripper) close gripper to width
Definition at line 106 of file pick_server.cpp.
void PickServer::pick | ( | const calvin_msgs::PickAndStoreGoalConstPtr & | goal | ) | [inline] |
Definition at line 183 of file pick_server.cpp.
bool PickServer::place | ( | std::string | id | ) | [inline] |
Definition at line 233 of file pick_server.cpp.
void PickServer::publish_grasps_as_markerarray | ( | std::vector< moveit_msgs::Grasp > | grasps | ) | [inline, protected] |
Definition at line 21 of file pick_server.cpp.
actionlib::SimpleActionServer<calvin_msgs::PickAndStoreAction>* PickServer::actionserver [protected] |
Definition at line 17 of file pick_server.cpp.
ros::Publisher PickServer::grasps_marker [protected] |
Definition at line 19 of file pick_server.cpp.
moveit::planning_interface::MoveGroup* PickServer::group [protected] |
Definition at line 18 of file pick_server.cpp.
ros::NodeHandle PickServer::nh [protected] |
Definition at line 16 of file pick_server.cpp.