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

The object recognition listener node object. More...

#include <ObjectRecognitionListener.h>

List of all members.

Public Member Functions

 ObjectRecognitionListener ()
 Creates a new ObjectRecognitionListener.
bool okay () const
 A check for a valid ObjectRecognitionListener.
virtual ~ObjectRecognitionListener ()
 Cleans up a ObjectRecognitionListener.

Static Public Attributes

static const bool DEFAULT_DEBUG = false
static const float DOWNSAMPLE_LEAF_SIZE = 0.01
static const double RECOGNITION_THRESHOLD = 0.5
static const double SAME_OBJECT_DIST_THRESHOLD = 0.2

Private Member Functions

void combineModels (const rail_manipulation_msgs::SegmentedObject &model1, const rail_manipulation_msgs::SegmentedObject &model2, rail_manipulation_msgs::SegmentedObject &combined) const
 Combine two models of the same type into a single model.
bool comparePointClouds (const sensor_msgs::PointCloud2 &pc1, const sensor_msgs::PointCloud2 &pc2) const
 Check if the two point clouds are the same.
bool removeObjectCallback (rail_pick_and_place_msgs::RemoveObject::Request &req, rail_pick_and_place_msgs::RemoveObject::Response &res)
 Callback for the remove object request.
void segmentedObjectsCallback (const rail_manipulation_msgs::SegmentedObjectList::ConstPtr &objects)
 The segmented objects callback.

Private Attributes

bool debug_
ros::Publisher debug_pub_
graspdb::Clientgraspdb_
ImageRecognizer image_recognizer_
boost::mutex mutex_
ros::NodeHandle node_
rail_manipulation_msgs::SegmentedObjectList object_list_
bool okay_
ros::NodeHandle private_node_
ros::Publisher recognized_objects_pub_
ros::ServiceServer remove_object_srv_
ros::Subscriber segmented_objects_sub_
bool use_image_recognition_

Detailed Description

The object recognition listener node object.

The object recognition listener will listen to a specified SegmentedObjectsArray topic and attempt to recognize all segmented objects. The new list are republished on a separate topic.

Definition at line 43 of file ObjectRecognitionListener.h.


Constructor & Destructor Documentation

Creates a new ObjectRecognitionListener.

Creates a new ObjectRecognitionListener with the associated topics.

Definition at line 26 of file ObjectRecognitionListener.cpp.

Cleans up a ObjectRecognitionListener.

Cleans up any connections used by the ObjectRecognitionListener.

Definition at line 77 of file ObjectRecognitionListener.cpp.


Member Function Documentation

void ObjectRecognitionListener::combineModels ( const rail_manipulation_msgs::SegmentedObject &  model1,
const rail_manipulation_msgs::SegmentedObject &  model2,
rail_manipulation_msgs::SegmentedObject &  combined 
) const [private]

Combine two models of the same type into a single model.

Take the two segmented object models and combine them into a single model. This is useful for when a single object has mistakenly been split into two models.

Parameters:
model1The first object model.
model2The second object model.
outThe combined model to set.

Definition at line 297 of file ObjectRecognitionListener.cpp.

bool ObjectRecognitionListener::comparePointClouds ( const sensor_msgs::PointCloud2 &  pc1,
const sensor_msgs::PointCloud2 &  pc2 
) const [private]

Check if the two point clouds are the same.

Checks if the data in the two point clouds are the same.

Parameters:
pc1The first point cloud.
pc2The second point cloud.
Returns:
Returns true if the data in pc1 is equal to the data in pc2.

Definition at line 290 of file ObjectRecognitionListener.cpp.

A check for a valid ObjectRecognitionListener.

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 84 of file ObjectRecognitionListener.cpp.

bool ObjectRecognitionListener::removeObjectCallback ( rail_pick_and_place_msgs::RemoveObject::Request &  req,
rail_pick_and_place_msgs::RemoveObject::Response &  res 
) [private]

Callback for the remove object request.

Remote the object from the segmented object list with a given ID. This will publish both an updated segmented object list.

Parameters:
reqThe request with the index to use.
resThe empty response (unused).
Returns:
Returns true if a valid index was provided.

Definition at line 266 of file ObjectRecognitionListener.cpp.

void ObjectRecognitionListener::segmentedObjectsCallback ( const rail_manipulation_msgs::SegmentedObjectList::ConstPtr &  objects) [private]

The segmented objects callback.

Take the current list of segmented objects and attempt to recognize each one. The new list is republished on the recognized objects topic.

Parameters:
objectsThe current list of segmented objects.

Definition at line 89 of file ObjectRecognitionListener.cpp.


Member Data Documentation

The debug and okay check flags.

Definition at line 127 of file ObjectRecognitionListener.h.

Definition at line 139 of file ObjectRecognitionListener.h.

If a topic should be created to display debug information such as pose arrays.

Definition at line 47 of file ObjectRecognitionListener.h.

Leaf size of the voxel grid for downsampling.

Definition at line 49 of file ObjectRecognitionListener.h.

The grasp database connection.

Definition at line 129 of file ObjectRecognitionListener.h.

Definition at line 145 of file ObjectRecognitionListener.h.

The main mutex for list modifications.

Definition at line 132 of file ObjectRecognitionListener.h.

The public and private ROS node handles.

Definition at line 135 of file ObjectRecognitionListener.h.

rail_manipulation_msgs::SegmentedObjectList rail::pick_and_place::ObjectRecognitionListener::object_list_ [private]

The most recent segmented objects.

Definition at line 143 of file ObjectRecognitionListener.h.

Definition at line 127 of file ObjectRecognitionListener.h.

Definition at line 135 of file ObjectRecognitionListener.h.

Confidence threshold for the recognizer.

Definition at line 53 of file ObjectRecognitionListener.h.

The recognized objects and debug publishers.

Definition at line 139 of file ObjectRecognitionListener.h.

The remove object server.

Definition at line 141 of file ObjectRecognitionListener.h.

The distance threshold for two point clouds being the same item.

Definition at line 51 of file ObjectRecognitionListener.h.

The listener for the segmented objects.

Definition at line 137 of file ObjectRecognitionListener.h.

Definition at line 147 of file ObjectRecognitionListener.h.


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


rail_recognition
Author(s): David Kent , Russell Toris , bhetherman
autogenerated on Sun Mar 6 2016 11:39:13