$search
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 | |
void | publishShapeMarker (const cob_3d_mapping_msgs::ShapeArray &sa) |
publishe markers to visualize shape in rviz | |
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 | pc2_pub_ |
ros::Publisher | s_marker_pub_ |
ros::Publisher | sa_pub_ |
ros::Subscriber | sa_sub_ |
SupportingPlaneExtraction | spe_ |
Definition at line 91 of file supporting_plane_extraction_node.cpp.
SupportingPlaneExtractionNode::SupportingPlaneExtractionNode | ( | ) | [inline] |
Definition at line 96 of file supporting_plane_extraction_node.cpp.
SupportingPlaneExtractionNode::~SupportingPlaneExtractionNode | ( | ) | [inline] |
void
Definition at line 109 of file supporting_plane_extraction_node.cpp.
void SupportingPlaneExtractionNode::callbackShapeArray | ( | const cob_3d_mapping_msgs::ShapeArray::ConstPtr | sa_ptr | ) | [inline] |
callback for ShapeArray messages
sa_ptr | pointer to the message |
Definition at line 143 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
config | data of configuration | |
level | bit descriptor which notifies which parameter changed |
Definition at line 125 of file supporting_plane_extraction_node.cpp.
bool SupportingPlaneExtractionNode::getMapService | ( | cob_3d_mapping_msgs::ShapeArray & | sa | ) | [inline] |
service offering geometry map of the scene
Definition at line 187 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
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 163 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
sa | input shape array | |
tables | output shape array containing tables |
Definition at line 272 of file supporting_plane_extraction_node.cpp.
void SupportingPlaneExtractionNode::publishShapeMarker | ( | const cob_3d_mapping_msgs::ShapeArray & | sa | ) | [inline] |
publishe markers to visualize shape in rviz
s | shape to be seen visually |
Definition at line 219 of file supporting_plane_extraction_node.cpp.
dynamic_reconfigure::Server<cob_3d_mapping_semantics::supporting_plane_extraction_nodeConfig> SupportingPlaneExtractionNode::config_server_ [protected] |
Dynamic Reconfigure server.
Definition at line 313 of file supporting_plane_extraction_node.cpp.
Definition at line 300 of file supporting_plane_extraction_node.cpp.
Definition at line 305 of file supporting_plane_extraction_node.cpp.
Definition at line 306 of file supporting_plane_extraction_node.cpp.
ros::Publisher SupportingPlaneExtractionNode::sa_pub_ [protected] |
Definition at line 304 of file supporting_plane_extraction_node.cpp.
Definition at line 303 of file supporting_plane_extraction_node.cpp.
Definition at line 315 of file supporting_plane_extraction_node.cpp.