Public Member Functions | Public Attributes | Protected Attributes
cob_3d_mapping::FOVSegmentationNode Class Reference

ROS node for FOV segmentation of a shape array. More...

#include <fov_segmentation_node.h>

List of all members.

Public Member Functions

void dynReconfCallback (cob_3d_fov_segmentation::fov_segmentationConfig &config, uint32_t level)
 Callback for dynamic reconfigure.
 FOVSegmentationNode ()
 Constructor.
void shapeCallback (const cob_3d_mapping_msgs::ShapeArray::ConstPtr &sa)
 Callback for the shape subscriber.
 ~FOVSegmentationNode ()

Public Attributes

ros::NodeHandle n_
 ROS node handle.

Protected Attributes

std::string camera_frame_
 The camera frame.
dynamic_reconfigure::Server
< cob_3d_fov_segmentation::fov_segmentationConfig > 
config_server_
 Dynamic Reconfigure server.
FieldOfView fov_
 Map containing geometrys (polygons,cylinders)
FOVSegmentation fov_seg_
 The FOV segmentation object.
ros::Publisher shape_pub_
 Publish Map array as shape message.
ros::Subscriber shape_sub_
 Subscription to shape message to be processed.
std::string target_frame_
 The target frame.
tf::TransformListener tf_listener_
 Retrieves transformations.

Detailed Description

ROS node for FOV segmentation of a shape array.

Node handles input Shape arrays and provides output Shape arrays.
Input topics: /tf, /shape_array
Output topics: /shape_array

Definition at line 86 of file fov_segmentation_node.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 78 of file fov_segmentation_node.cpp.

brief Destructor

Definition at line 96 of file fov_segmentation_node.h.


Member Function Documentation

void FOVSegmentationNode::dynReconfCallback ( cob_3d_fov_segmentation::fov_segmentationConfig &  config,
uint32_t  level 
)

Callback for dynamic reconfigure.

everytime the dynamic reconfiguration changes this function will be called

Parameters:
instinstance of AggregatePointMap which parameters should be changed
configdata of configuration
levelbit descriptor which notifies which parameter changed
Returns:
nothing

Definition at line 86 of file fov_segmentation_node.cpp.

void FOVSegmentationNode::shapeCallback ( const cob_3d_mapping_msgs::ShapeArray::ConstPtr &  sa)

Callback for the shape subscriber.

Parameters:
[in]Theincoming shape array.

Definition at line 99 of file fov_segmentation_node.cpp.


Member Data Documentation

The camera frame.

Definition at line 139 of file fov_segmentation_node.h.

dynamic_reconfigure::Server<cob_3d_fov_segmentation::fov_segmentationConfig> cob_3d_mapping::FOVSegmentationNode::config_server_ [protected]

Dynamic Reconfigure server.

Definition at line 134 of file fov_segmentation_node.h.

Map containing geometrys (polygons,cylinders)

Definition at line 136 of file fov_segmentation_node.h.

The FOV segmentation object.

Definition at line 137 of file fov_segmentation_node.h.

ROS node handle.

Definition at line 123 of file fov_segmentation_node.h.

Publish Map array as shape message.

Definition at line 127 of file fov_segmentation_node.h.

Subscription to shape message to be processed.

Definition at line 126 of file fov_segmentation_node.h.

The target frame.

Definition at line 140 of file fov_segmentation_node.h.

Retrieves transformations.

Definition at line 129 of file fov_segmentation_node.h.


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


cob_3d_fov_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:19