Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
rail::pick_and_place::GraspCollector Class Reference

The main grasp collector node object. More...

#include <GraspCollector.h>

List of all members.

Public Member Functions

 GraspCollector ()
 Create a GraspCollector and associated ROS information.
bool okay () const
 A check for a valid GraspCollector.
virtual ~GraspCollector ()
 Cleans up a GraspCollector.

Static Public Attributes

static const int AC_WAIT_TIME = 10
static const bool DEFAULT_DEBUG = false

Private Member Functions

void graspAndStore (const rail_pick_and_place_msgs::GraspAndStoreGoalConstPtr &goal)
 Callback for the store grasp action server.
void segmentedObjectsCallback (const rail_manipulation_msgs::SegmentedObjectList::Ptr &object_list)
 Callback for the segmented objects topic.

Private Attributes

ros::Duration ac_wait_time_
actionlib::SimpleActionServer
< rail_pick_and_place_msgs::GraspAndStoreAction > 
as_
bool debug_
ros::Publisher debug_pub_
std::string eef_frame_id_
graspdb::Clientgraspdb_
actionlib::SimpleActionClient
< rail_manipulation_msgs::GripperAction > * 
gripper_ac_
actionlib::SimpleActionClient
< rail_manipulation_msgs::LiftAction > * 
lift_ac_
boost::mutex mutex_
ros::NodeHandle node_
rail_manipulation_msgs::SegmentedObjectList::Ptr object_list_
bool okay_
ros::NodeHandle private_node_
std::string robot_fixed_frame_id_
ros::Subscriber segmented_objects_sub_
tf2_ros::Buffer tf_buffer_
tf2_ros::TransformListener tf_listener_
actionlib::SimpleActionClient
< rail_manipulation_msgs::VerifyGraspAction > * 
verify_grasp_ac_

Detailed Description

The main grasp collector node object.

The grasp collector is responsible for capturing and storing grasps. An action server is started is the main entry point to grasp collecting.

Definition at line 45 of file GraspCollector.h.


Constructor & Destructor Documentation

Create a GraspCollector and associated ROS information.

Creates a ROS node handle, subscribes to the relevant topics and servers, and creates a client to the grasp database.

Definition at line 22 of file GraspCollector.cpp.

Cleans up a GraspCollector.

Cleans up any connections used by the GraspCollector.

Definition at line 83 of file GraspCollector.cpp.


Member Function Documentation

void GraspCollector::graspAndStore ( const rail_pick_and_place_msgs::GraspAndStoreGoalConstPtr &  goal) [private]

Callback for the store grasp action server.

The store grasp action will close the gripper, lift the arm (if specified), verify the grasp (if specified), and store the grasp/point cloud data in the grasp database.

Parameters:
goalThe goal object specifying the parameters.

Definition at line 99 of file GraspCollector.cpp.

bool GraspCollector::okay ( ) const

A check for a valid GraspCollector.

This function will return true if the appropriate connections were created successfully during initialization.

Returns:
True if the appropriate connections were created successfully during initialization.

Definition at line 94 of file GraspCollector.cpp.

void GraspCollector::segmentedObjectsCallback ( const rail_manipulation_msgs::SegmentedObjectList::Ptr &  object_list) [private]

Callback for the segmented objects topic.

Stores the object list internally.

Parameters:
object_listThe object list returned from the segmented objects topic.

Definition at line 270 of file GraspCollector.cpp.


Member Data Documentation

The default wait time for action servers in seconds.

Definition at line 51 of file GraspCollector.h.

The action client timeout.

Definition at line 129 of file GraspCollector.h.

actionlib::SimpleActionServer<rail_pick_and_place_msgs::GraspAndStoreAction> rail::pick_and_place::GraspCollector::as_ [private]

The main grasp collection action server.

Definition at line 116 of file GraspCollector.h.

The debug and okay check flags.

Definition at line 101 of file GraspCollector.h.

The debug topic publisher.

Definition at line 110 of file GraspCollector.h.

If a topic should be created to display debug information such as point clouds.

Definition at line 49 of file GraspCollector.h.

Definition at line 103 of file GraspCollector.h.

The grasp database connection.

Definition at line 105 of file GraspCollector.h.

actionlib::SimpleActionClient<rail_manipulation_msgs::GripperAction>* rail::pick_and_place::GraspCollector::gripper_ac_ [private]

The gripper action client.

Definition at line 118 of file GraspCollector.h.

actionlib::SimpleActionClient<rail_manipulation_msgs::LiftAction>* rail::pick_and_place::GraspCollector::lift_ac_ [private]

The lift action client.

Definition at line 120 of file GraspCollector.h.

Mutex for locking on the segmented object list.

Definition at line 98 of file GraspCollector.h.

The public and private ROS node handles.

Definition at line 108 of file GraspCollector.h.

rail_manipulation_msgs::SegmentedObjectList::Ptr rail::pick_and_place::GraspCollector::object_list_ [private]

The most recent segmented objects.

Definition at line 114 of file GraspCollector.h.

Definition at line 101 of file GraspCollector.h.

Definition at line 108 of file GraspCollector.h.

Frame IDs to use.

Definition at line 103 of file GraspCollector.h.

The listener for the segmented objects.

Definition at line 112 of file GraspCollector.h.

The trasnform tree buffer.

Definition at line 125 of file GraspCollector.h.

The trasnform client.

Definition at line 127 of file GraspCollector.h.

actionlib::SimpleActionClient<rail_manipulation_msgs::VerifyGraspAction>* rail::pick_and_place::GraspCollector::verify_grasp_ac_ [private]

The verify grasp action client.

Definition at line 122 of file GraspCollector.h.


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


rail_grasp_collection
Author(s): Russell Toris , David Kent
autogenerated on Sun Mar 6 2016 11:39:03