Public Member Functions | |
TabletopObjectRecognizer (ros::NodeHandle nh) | |
Subscribes to and advertises topics; initializes fitter. | |
~TabletopObjectRecognizer () | |
Empty stub. | |
Private Member Functions | |
bool | addExclusionCB (AddModelExclusion::Request &request, AddModelExclusion::Response &response) |
bool | clearExclusionsCB (ClearExclusionsList::Request &request, ClearExclusionsList::Response &response) |
void | clearOldMarkers (std::string frame_id) |
Clears old published markers and remembers the current number of published markers. | |
template<class PointCloudType > | |
double | fitClusterDistance (const ModelFitInfo &m, const PointCloudType &cluster) |
Helper function that returns the distance along the plane between a fit model and a cluster. | |
double | fitDistance (const ModelFitInfo &m1, const ModelFitInfo &m2) |
Helper function that returns the distance along the plane between two fit models. | |
bool | negateExclusionsCB (NegateExclusions::Request &request, NegateExclusions::Response &response) |
template<class PointCloudType > | |
void | objectDetection (std::vector< PointCloudType > &clusters, int num_models, const Table &table, bool perform_fit_merge, TabletopObjectRecognition::Response &response) |
Performs object detection on the given clusters, can also merge clusters based on detection result. | |
void | publishFitMarkers (const std::vector< household_objects_database_msgs::DatabaseModelPoseList > &potential_models, const Table &table) |
Publishes markers for all fits. | |
bool | serviceCallback (TabletopObjectRecognition::Request &request, TabletopObjectRecognition::Response &response) |
Callback for service calls. | |
Private Attributes | |
ros::ServiceServer | add_model_exclusion_srv_ |
Service server for adding to the model exclusion set. | |
ros::ServiceServer | clear_model_exclusions_srv_ |
Service server for clearing the exclusion set. | |
ros::Subscriber | cloud_new_sub_ |
Listener for incoming new-style point clouds. | |
int | current_marker_id_ |
The current marker being published. | |
ExhaustiveFitDetector < IterativeTranslationFitter > | detector_ |
The instance of the detector used for all detecting tasks. | |
double | fit_merge_threshold_ |
The threshold for merging two models that were fit very close to each other. | |
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. | |
double | min_marker_quality_ |
Fit results below this quality are not published as markers. | |
std::string | model_set_ |
Whether to use a reduced model set from the database. | |
ros::ServiceServer | negate_exclusions_srv_ |
Service server for negating the exclusion set. | |
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. |
Definition at line 62 of file tabletop_object_recognition.cpp.
Subscribes to and advertises topics; initializes fitter.
Definition at line 144 of file tabletop_object_recognition.cpp.
Empty stub.
Definition at line 141 of file tabletop_object_recognition.cpp.
bool tabletop_object_detector::TabletopObjectRecognizer::addExclusionCB | ( | AddModelExclusion::Request & | request, |
AddModelExclusion::Response & | response | ||
) | [private] |
Definition at line 186 of file tabletop_object_recognition.cpp.
bool tabletop_object_detector::TabletopObjectRecognizer::clearExclusionsCB | ( | ClearExclusionsList::Request & | request, |
ClearExclusionsList::Response & | response | ||
) | [private] |
Definition at line 178 of file tabletop_object_recognition.cpp.
void tabletop_object_detector::TabletopObjectRecognizer::clearOldMarkers | ( | std::string | frame_id | ) | [private] |
Clears old published markers and remembers the current number of published markers.
Definition at line 387 of file tabletop_object_recognition.cpp.
double tabletop_object_detector::TabletopObjectRecognizer::fitClusterDistance | ( | const ModelFitInfo & | m, |
const PointCloudType & | cluster | ||
) | [private] |
Helper function that returns the distance along the plane between a fit model and a cluster.
Definition at line 416 of file tabletop_object_recognition.cpp.
double tabletop_object_detector::TabletopObjectRecognizer::fitDistance | ( | const ModelFitInfo & | m1, |
const ModelFitInfo & | m2 | ||
) | [private] |
Helper function that returns the distance along the plane between two fit models.
Definition at line 407 of file tabletop_object_recognition.cpp.
bool tabletop_object_detector::TabletopObjectRecognizer::negateExclusionsCB | ( | NegateExclusions::Request & | request, |
NegateExclusions::Response & | response | ||
) | [private] |
Definition at line 194 of file tabletop_object_recognition.cpp.
void tabletop_object_detector::TabletopObjectRecognizer::objectDetection | ( | std::vector< PointCloudType > & | clusters, |
int | num_models, | ||
const Table & | table, | ||
bool | perform_fit_merge, | ||
TabletopObjectRecognition::Response & | response | ||
) | [private] |
Performs object detection on the given clusters, can also merge clusters based on detection result.
Performs the detection on each of the clusters, and populates the returned message.
Definition at line 247 of file tabletop_object_recognition.cpp.
void tabletop_object_detector::TabletopObjectRecognizer::publishFitMarkers | ( | const std::vector< household_objects_database_msgs::DatabaseModelPoseList > & | potential_models, |
const Table & | table | ||
) | [private] |
Publishes markers for all fits.
Definition at line 356 of file tabletop_object_recognition.cpp.
bool tabletop_object_detector::TabletopObjectRecognizer::serviceCallback | ( | TabletopObjectRecognition::Request & | request, |
TabletopObjectRecognition::Response & | response | ||
) | [private] |
Callback for service calls.
Processes the latest point cloud and gives back the resulting array of models.
Definition at line 204 of file tabletop_object_recognition.cpp.
ros::ServiceServer tabletop_object_detector::TabletopObjectRecognizer::add_model_exclusion_srv_ [private] |
Service server for adding to the model exclusion set.
Definition at line 77 of file tabletop_object_recognition.cpp.
ros::ServiceServer tabletop_object_detector::TabletopObjectRecognizer::clear_model_exclusions_srv_ [private] |
Service server for clearing the exclusion set.
Definition at line 80 of file tabletop_object_recognition.cpp.
Listener for incoming new-style point clouds.
Definition at line 70 of file tabletop_object_recognition.cpp.
The current marker being published.
Definition at line 91 of file tabletop_object_recognition.cpp.
ExhaustiveFitDetector<IterativeTranslationFitter> tabletop_object_detector::TabletopObjectRecognizer::detector_ [private] |
The instance of the detector used for all detecting tasks.
Definition at line 94 of file tabletop_object_recognition.cpp.
The threshold for merging two models that were fit very close to each other.
Definition at line 100 of file tabletop_object_recognition.cpp.
ros::ServiceClient tabletop_object_detector::TabletopObjectRecognizer::get_model_mesh_srv_ [private] |
Service client for getting a mesh from the database.
Definition at line 84 of file tabletop_object_recognition.cpp.
A tf transform listener.
Definition at line 103 of file tabletop_object_recognition.cpp.
Publisher for markers.
Definition at line 72 of file tabletop_object_recognition.cpp.
Fit results below this quality are not published as markers.
Definition at line 87 of file tabletop_object_recognition.cpp.
std::string tabletop_object_detector::TabletopObjectRecognizer::model_set_ [private] |
Whether to use a reduced model set from the database.
Definition at line 97 of file tabletop_object_recognition.cpp.
ros::ServiceServer tabletop_object_detector::TabletopObjectRecognizer::negate_exclusions_srv_ [private] |
Service server for negating the exclusion set.
Definition at line 82 of file tabletop_object_recognition.cpp.
The node handle.
Definition at line 66 of file tabletop_object_recognition.cpp.
Used to remember the number of markers we publish so we can delete them later.
Definition at line 89 of file tabletop_object_recognition.cpp.
ros::ServiceServer tabletop_object_detector::TabletopObjectRecognizer::object_recognition_srv_ [private] |
Service server for object detection.
Definition at line 74 of file tabletop_object_recognition.cpp.
Node handle in the private namespace.
Definition at line 68 of file tabletop_object_recognition.cpp.