Public Member Functions | Public Attributes
pickAndPlace Class Reference

#include <pick_and_place.h>

List of all members.

Public Member Functions

void objectCallback (const rail_segmentation::SegmentedObjectList &list)
 pickAndPlace ()
bool pickup (rail_pick_and_place_msgs::PickupObject::Request &req, rail_pick_and_place_msgs::PickupObject::Response &res)
bool pickupSegmented (rail_pick_and_place_msgs::PickupSegmentedObject::Request &req, rail_pick_and_place_msgs::PickupSegmentedObject::Response &res)

Public Attributes

actionlib::SimpleActionClient
< wpi_jaco_msgs::HomeArmAction > 
acHome
ros::ServiceClient graspRecognizedClient
ros::NodeHandle n
rail_segmentation::SegmentedObjectList objectList
ros::Subscriber objectSubscriber
ros::ServiceServer pickupSegmentedServer
ros::ServiceServer pickupServer
ros::ServiceClient recognizeAndGraspClient
ros::ServiceClient segmentClient

Detailed Description

Definition at line 13 of file pick_and_place.h.


Constructor & Destructor Documentation

Constructor

Definition at line 5 of file pick_and_place.cpp.


Member Function Documentation

void pickAndPlace::objectCallback ( const rail_segmentation::SegmentedObjectList &  list)

Callback for segmented object list

Parameters:
objectListthe list of segmented objects

Definition at line 108 of file pick_and_place.cpp.

bool pickAndPlace::pickup ( rail_pick_and_place_msgs::PickupObject::Request &  req,
rail_pick_and_place_msgs::PickupObject::Response &  res 
)

High level call to recognize and pickup a specified object

Parameters:
reqservice request including the name of the object to be picked up
resservice response denoting pickup success as a boolean value
Returns:
true on successful service callback

Definition at line 21 of file pick_and_place.cpp.

bool pickAndPlace::pickupSegmented ( rail_pick_and_place_msgs::PickupSegmentedObject::Request &  req,
rail_pick_and_place_msgs::PickupSegmentedObject::Response &  res 
)

High level call to pickup an already segmented but unrecognized object

Parameters:
reqservice request
resservice response denoting pickup success as a boolean value
Returns:
true on successful service callback

Definition at line 114 of file pick_and_place.cpp.


Member Data Documentation

actionlib::SimpleActionClient<wpi_jaco_msgs::HomeArmAction> pickAndPlace::acHome

Definition at line 28 of file pick_and_place.h.

Definition at line 26 of file pick_and_place.h.

Definition at line 17 of file pick_and_place.h.

rail_segmentation::SegmentedObjectList pickAndPlace::objectList

Definition at line 30 of file pick_and_place.h.

Definition at line 19 of file pick_and_place.h.

Definition at line 22 of file pick_and_place.h.

Definition at line 21 of file pick_and_place.h.

Definition at line 24 of file pick_and_place.h.

Definition at line 25 of file pick_and_place.h.


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


rail_pick_and_place_wrapper
Author(s): David Kent
autogenerated on Tue Mar 3 2015 19:18:44