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::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 | |
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::Publisher | sa_pub_ |
ros::Subscriber | sa_sub_ |
std::string | target_frame_id_ |
TableExtraction | te_ |
Definition at line 94 of file table_extraction_node.cpp.
TableExtractionNode::TableExtractionNode | ( | ) | [inline] |
Definition at line 99 of file table_extraction_node.cpp.
TableExtractionNode::~TableExtractionNode | ( | ) | [inline] |
void
Definition at line 111 of file table_extraction_node.cpp.
void TableExtractionNode::callbackShapeArray | ( | const cob_3d_mapping_msgs::ShapeArray::ConstPtr | sa_ptr | ) | [inline] |
callback for ShapeArray messages
sa_ptr | pointer to the message |
Definition at line 147 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
config | data of configuration |
level | bit descriptor which notifies which parameter changed |
Definition at line 127 of file table_extraction_node.cpp.
bool TableExtractionNode::getMapService | ( | cob_3d_mapping_msgs::ShapeArray & | sa | ) | [inline] |
service offering geometry map of the scene
Definition at line 200 of file table_extraction_node.cpp.
bool TableExtractionNode::getTablesService | ( | cob_3d_mapping_msgs::GetTablesRequest & | req, |
cob_3d_mapping_msgs::GetTablesResponse & | res | ||
) | [inline] |
service offering table object candidates
req | request for objects of a class (table objects in this case) |
res | response of the service which is possible table object candidates |
Definition at line 172 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
sa | input shape array |
tables | output shape array containing tables |
Definition at line 233 of file table_extraction_node.cpp.
dynamic_reconfigure::Server<cob_3d_mapping_semantics::table_extraction_nodeConfig> TableExtractionNode::config_server_ [protected] |
Dynamic Reconfigure server.
Definition at line 266 of file table_extraction_node.cpp.
Definition at line 261 of file table_extraction_node.cpp.
Definition at line 256 of file table_extraction_node.cpp.
ros::Publisher TableExtractionNode::sa_pub_ [protected] |
Definition at line 260 of file table_extraction_node.cpp.
ros::Subscriber TableExtractionNode::sa_sub_ [protected] |
Definition at line 259 of file table_extraction_node.cpp.
std::string TableExtractionNode::target_frame_id_ [protected] |
Definition at line 270 of file table_extraction_node.cpp.
TableExtraction TableExtractionNode::te_ [protected] |
Definition at line 268 of file table_extraction_node.cpp.