$search

tabletop_vfh_cluster_detector::TabletopVFHClassifier Class Reference

List of all members.

Public Member Functions

 TabletopVFHClassifier (ros::NodeHandle nh)
 Advertise service.
 ~TabletopVFHClassifier ()
 Empty stub.

Private Member Functions

void clearOldMarkers (std::string frame_id)
void publishFitMarkers (const std::vector< household_objects_database_msgs::DatabaseModelPoseList > &potential_models, std::string frame_id)
bool serviceCallback (TabletopObjectRecognition::Request &request, TabletopObjectRecognition::Response &response)
 Callback for service calls.

Private Attributes

int current_marker_id_
 The current marker being published.
ros::ServiceClient get_model_mesh_srv_
 Service client for getting a mesh from the database.
tf::TransformListener listener_
 A tf transform listener.
ros::Publisher marker_pub_
 Publisher for markers.
ros::NodeHandle nh_
 The node handle.
int num_markers_published_
 Used to remember the number of markers we publish so we can delete them later.
ros::ServiceServer object_recognition_srv_
 Service server for object detection.
ros::NodeHandle priv_nh_
 Node handle in the private namespace.
vfh_recognizer_db::VFHRecognizerDB
< flann::HistIntersectionUnionDistance > 
vfh_recognizer

Detailed Description

Definition at line 24 of file tabletop_vfh_classifier.cpp.


Constructor & Destructor Documentation

tabletop_vfh_cluster_detector::TabletopVFHClassifier::TabletopVFHClassifier ( ros::NodeHandle  nh  ) 

Advertise service.

Definition at line 70 of file tabletop_vfh_classifier.cpp.

tabletop_vfh_cluster_detector::TabletopVFHClassifier::~TabletopVFHClassifier (  )  [inline]

Empty stub.

Definition at line 65 of file tabletop_vfh_classifier.cpp.


Member Function Documentation

void tabletop_vfh_cluster_detector::TabletopVFHClassifier::clearOldMarkers ( std::string  frame_id  )  [private]

Definition at line 132 of file tabletop_vfh_classifier.cpp.

void tabletop_vfh_cluster_detector::TabletopVFHClassifier::publishFitMarkers ( const std::vector< household_objects_database_msgs::DatabaseModelPoseList > &  potential_models,
std::string  frame_id 
) [private]

Definition at line 101 of file tabletop_vfh_classifier.cpp.

bool tabletop_vfh_cluster_detector::TabletopVFHClassifier::serviceCallback ( TabletopObjectRecognition::Request request,
TabletopObjectRecognition::Response response 
) [private]

Callback for service calls.

Definition at line 154 of file tabletop_vfh_classifier.cpp.


Member Data Documentation

The current marker being published.

Definition at line 44 of file tabletop_vfh_classifier.cpp.

Service client for getting a mesh from the database.

Definition at line 34 of file tabletop_vfh_classifier.cpp.

A tf transform listener.

Definition at line 39 of file tabletop_vfh_classifier.cpp.

Publisher for markers.

Definition at line 37 of file tabletop_vfh_classifier.cpp.

The node handle.

Definition at line 28 of file tabletop_vfh_classifier.cpp.

Used to remember the number of markers we publish so we can delete them later.

Definition at line 42 of file tabletop_vfh_classifier.cpp.

Service server for object detection.

Definition at line 32 of file tabletop_vfh_classifier.cpp.

Node handle in the private namespace.

Definition at line 30 of file tabletop_vfh_classifier.cpp.

Definition at line 47 of file tabletop_vfh_classifier.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


tabletop_vfh_cluster_detector
Author(s): Aitor Aldoma
autogenerated on Tue Mar 5 15:33:41 2013