Public Member Functions | Public Attributes | Protected Attributes
SupportingPlaneExtractionNode Class Reference

List of all members.

Public Member Functions

void callbackShapeArray (const cob_3d_mapping_msgs::ShapeArray::ConstPtr sa_ptr)
 callback for ShapeArray messages
void dynReconfCallback (cob_3d_mapping_semantics::supporting_plane_extraction_nodeConfig &config, uint32_t level)
 callback for dynamic reconfigure
bool getMapService (cob_3d_mapping_msgs::ShapeArray &sa)
 service offering geometry map of the scene
bool getTablesService (cob_3d_mapping_msgs::GetObjectsOfClassRequest &req, cob_3d_mapping_msgs::GetObjectsOfClassResponse &res)
 service offering table object candidates
void processShapeArray (const cob_3d_mapping_msgs::ShapeArray &sa, cob_3d_mapping_msgs::ShapeArray &sup_planes)
 processes a shape array in order to find tables
 SupportingPlaneExtractionNode ()
 ~SupportingPlaneExtractionNode ()

Public Attributes

ros::NodeHandle n_

Protected Attributes

dynamic_reconfigure::Server
< cob_3d_mapping_semantics::supporting_plane_extraction_nodeConfig > 
config_server_
 Dynamic Reconfigure server.
ros::Publisher sa_pub_
ros::Subscriber sa_sub_
SupportingPlaneExtraction spe_

Detailed Description

Definition at line 87 of file supporting_plane_extraction_node.cpp.


Constructor & Destructor Documentation

Definition at line 92 of file supporting_plane_extraction_node.cpp.

void

Definition at line 102 of file supporting_plane_extraction_node.cpp.


Member Function Documentation

void SupportingPlaneExtractionNode::callbackShapeArray ( const cob_3d_mapping_msgs::ShapeArray::ConstPtr  sa_ptr) [inline]

callback for ShapeArray messages

Parameters:
sa_ptrpointer to the message
Returns:
nothing

Definition at line 136 of file supporting_plane_extraction_node.cpp.

void SupportingPlaneExtractionNode::dynReconfCallback ( cob_3d_mapping_semantics::supporting_plane_extraction_nodeConfig &  config,
uint32_t  level 
) [inline]

callback for dynamic reconfigure

everytime the dynamic reconfiguration changes this function will be called

Parameters:
configdata of configuration
levelbit descriptor which notifies which parameter changed
Returns:
nothing

Definition at line 118 of file supporting_plane_extraction_node.cpp.

bool SupportingPlaneExtractionNode::getMapService ( cob_3d_mapping_msgs::ShapeArray &  sa) [inline]

service offering geometry map of the scene

Returns:
true if service successful

Definition at line 178 of file supporting_plane_extraction_node.cpp.

bool SupportingPlaneExtractionNode::getTablesService ( cob_3d_mapping_msgs::GetObjectsOfClassRequest &  req,
cob_3d_mapping_msgs::GetObjectsOfClassResponse &  res 
) [inline]

service offering table object candidates

Parameters:
reqrequest for objects of a class (table objects in this case)
resresponse of the service which is possible table object candidates
Returns:
true if service successful

Definition at line 155 of file supporting_plane_extraction_node.cpp.

void SupportingPlaneExtractionNode::processShapeArray ( const cob_3d_mapping_msgs::ShapeArray &  sa,
cob_3d_mapping_msgs::ShapeArray &  sup_planes 
) [inline]

processes a shape array in order to find tables

Parameters:
sainput shape array
tablesoutput shape array containing tables
Returns:
nothing

Definition at line 212 of file supporting_plane_extraction_node.cpp.


Member Data Documentation

dynamic_reconfigure::Server<cob_3d_mapping_semantics::supporting_plane_extraction_nodeConfig> SupportingPlaneExtractionNode::config_server_ [protected]

Dynamic Reconfigure server.

Definition at line 244 of file supporting_plane_extraction_node.cpp.

Definition at line 235 of file supporting_plane_extraction_node.cpp.

Definition at line 239 of file supporting_plane_extraction_node.cpp.

Definition at line 238 of file supporting_plane_extraction_node.cpp.

Definition at line 246 of file supporting_plane_extraction_node.cpp.


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


cob_3d_mapping_semantics
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:34