$search

TableExtractionNode 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::table_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
bool getTablesService2 (cob_3d_mapping_msgs::GetTablesRequest &req, cob_3d_mapping_msgs::GetTablesResponse &res)
 service offering table object candidates
void processMap (const cob_3d_mapping_msgs::ShapeArray &sa, cob_3d_mapping_msgs::ShapeArray &tables)
 processes a shape array in order to find tables
void publishShapeMarker (const cob_3d_mapping_msgs::ShapeArray &sa)
 publishe markers to visualize shape in rviz
 TableExtractionNode ()
 ~TableExtractionNode ()

Public Attributes

ros::NodeHandle n_

Protected Attributes

dynamic_reconfigure::Server
< cob_3d_mapping_semantics::table_extraction_nodeConfig > 
config_server_
 Dynamic Reconfigure server.
ros::ServiceServer get_tables_server_
ros::ServiceServer get_tables_server_2_
ros::Publisher pc2_pub_
ros::Publisher s_marker_pub_
ros::Publisher sa_pub_
ros::Subscriber sa_sub_
unsigned int table_ctr_
unsigned int table_ctr_old_
std::string target_frame_id_
TableExtraction te_

Detailed Description

Definition at line 91 of file table_extraction_node.cpp.


Constructor & Destructor Documentation

TableExtractionNode::TableExtractionNode (  )  [inline]

Definition at line 96 of file table_extraction_node.cpp.

TableExtractionNode::~TableExtractionNode (  )  [inline]

void

Definition at line 132 of file table_extraction_node.cpp.


Member Function Documentation

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

callback for ShapeArray messages

Parameters:
sa_ptr pointer to the message
Returns:
nothing

Definition at line 168 of file table_extraction_node.cpp.

void TableExtractionNode::dynReconfCallback ( cob_3d_mapping_semantics::table_extraction_nodeConfig &  config,
uint32_t  level 
) [inline]

callback for dynamic reconfigure

everytime the dynamic reconfiguration changes this function will be called

Parameters:
config data of configuration
level bit descriptor which notifies which parameter changed
Returns:
nothing

Definition at line 148 of file table_extraction_node.cpp.

bool TableExtractionNode::getMapService ( cob_3d_mapping_msgs::ShapeArray sa  )  [inline]

service offering geometry map of the scene

Returns:
true if service successful

Definition at line 297 of file table_extraction_node.cpp.

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

service offering table object candidates

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

Definition at line 195 of file table_extraction_node.cpp.

bool TableExtractionNode::getTablesService2 ( cob_3d_mapping_msgs::GetTablesRequest req,
cob_3d_mapping_msgs::GetTablesResponse res 
) [inline]

service offering table object candidates

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

Definition at line 222 of file table_extraction_node.cpp.

void TableExtractionNode::processMap ( const cob_3d_mapping_msgs::ShapeArray sa,
cob_3d_mapping_msgs::ShapeArray tables 
) [inline]

processes a shape array in order to find tables

Parameters:
sa input shape array
tables output shape array containing tables
Returns:
nothing

Definition at line 389 of file table_extraction_node.cpp.

void TableExtractionNode::publishShapeMarker ( const cob_3d_mapping_msgs::ShapeArray sa  )  [inline]

publishe markers to visualize shape in rviz

Parameters:
s shape to be seen visually
Returns:
nothing

Definition at line 329 of file table_extraction_node.cpp.


Member Data Documentation

dynamic_reconfigure::Server<cob_3d_mapping_semantics::table_extraction_nodeConfig> TableExtractionNode::config_server_ [protected]

Dynamic Reconfigure server.

Definition at line 449 of file table_extraction_node.cpp.

Definition at line 442 of file table_extraction_node.cpp.

Definition at line 443 of file table_extraction_node.cpp.

Definition at line 435 of file table_extraction_node.cpp.

Definition at line 440 of file table_extraction_node.cpp.

Definition at line 441 of file table_extraction_node.cpp.

Definition at line 439 of file table_extraction_node.cpp.

Definition at line 438 of file table_extraction_node.cpp.

unsigned int TableExtractionNode::table_ctr_ [protected]

Definition at line 458 of file table_extraction_node.cpp.

unsigned int TableExtractionNode::table_ctr_old_ [protected]

Definition at line 459 of file table_extraction_node.cpp.

std::string TableExtractionNode::target_frame_id_ [protected]

Definition at line 453 of file table_extraction_node.cpp.

Definition at line 451 of file table_extraction_node.cpp.


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


cob_3d_mapping_semantics
Author(s): Georg Arbeiter
autogenerated on Fri Mar 1 15:30:19 2013