$search

fast_plane_detection::FastPlaneDetector Class Reference

List of all members.

Public Member Functions

 FastPlaneDetector (int buffer_size)
void planeCallback (const stereo_msgs::DisparityImage::ConstPtr &disparity_image)
 Callback for disparity image messages.
 ~FastPlaneDetector ()

Public Attributes

Plane plane_
 the plane

Private Member Functions

void clearOldMarkers (std::string frame_id)
void maskDisparityImage (const stereo_msgs::DisparityImage::ConstPtr &disparity_image, const sensor_msgs::Image &labels, stereo_msgs::DisparityImage &masked_disparity)

Private Attributes

int buffer_size_
 Buffer size for callbacks.
sensor_msgs::CameraInfo::ConstPtr camera_info_
 camera info (needs to be obtained only once)
ros::Subscriber camera_info_sub_
 Subscriber to camera info.
std::string camera_info_topic_
int current_marker_id_
 The current marker being published.
stereo_msgs::DisparityImage::ConstPtr disparity_image_
 disparity image (needs to be obtained always)
ros::Publisher disparity_image_pub_
 Publisher to Filtered Disparity Images.
ros::Subscriber disparity_image_sub_
 Subscriber to disparity images.
std::string disparity_image_topic_
bool find_table_
 whether to restrict search for plane to table like orientation
image_transport::Publisher image_pub_
 Publishing images (for debug only).
int inlier_threshold_
 Minimum number of points necessary to pass a plane detection.
int num_markers_published_
 Used to remember the number of markers we publish so we can delete them later.
PlaneDetectionplane_detect_
 plane detection object
ros::Publisher plane_marker_pub_
 Publisher to Plane Parameters.
ros::Publisher plane_msg_pub_
 Publisher to Plane Parameters.
PlaneTransformplane_transform_
 object for transforming from x,y,d space to x,y,z
ros::NodeHandle priv_nh_
 Node handle in the private namespace.
ros::NodeHandle root_nh_
 The node handle.
double up_direction_
 Which direction along optical axis is pointing best towards up direction.

Detailed Description

Definition at line 54 of file fast_plane_detector_node.cpp.


Constructor & Destructor Documentation

fast_plane_detection::FastPlaneDetector::FastPlaneDetector ( int  buffer_size  ) 

Publisher for labeled images

Definition at line 141 of file fast_plane_detector_node.cpp.

fast_plane_detection::FastPlaneDetector::~FastPlaneDetector (  ) 

Definition at line 219 of file fast_plane_detector_node.cpp.


Member Function Documentation

void fast_plane_detection::FastPlaneDetector::clearOldMarkers ( std::string  frame_id  )  [private]

Definition at line 297 of file fast_plane_detector_node.cpp.

void fast_plane_detection::FastPlaneDetector::maskDisparityImage ( const stereo_msgs::DisparityImage::ConstPtr disparity_image,
const sensor_msgs::Image labels,
stereo_msgs::DisparityImage masked_disparity 
) [private]

Definition at line 319 of file fast_plane_detector_node.cpp.

void fast_plane_detection::FastPlaneDetector::planeCallback ( const stereo_msgs::DisparityImage::ConstPtr disparity_image  ) 

Callback for disparity image messages.

Definition at line 223 of file fast_plane_detector_node.cpp.


Member Data Documentation

Buffer size for callbacks.

Definition at line 80 of file fast_plane_detector_node.cpp.

camera info (needs to be obtained only once)

Definition at line 86 of file fast_plane_detector_node.cpp.

Subscriber to camera info.

Definition at line 72 of file fast_plane_detector_node.cpp.

Definition at line 73 of file fast_plane_detector_node.cpp.

The current marker being published.

Definition at line 120 of file fast_plane_detector_node.cpp.

disparity image (needs to be obtained always)

Definition at line 83 of file fast_plane_detector_node.cpp.

Publisher to Filtered Disparity Images.

Definition at line 95 of file fast_plane_detector_node.cpp.

Subscriber to disparity images.

Definition at line 76 of file fast_plane_detector_node.cpp.

Definition at line 77 of file fast_plane_detector_node.cpp.

whether to restrict search for plane to table like orientation

Definition at line 106 of file fast_plane_detector_node.cpp.

Publishing images (for debug only).

Definition at line 98 of file fast_plane_detector_node.cpp.

Minimum number of points necessary to pass a plane detection.

Definition at line 115 of file fast_plane_detector_node.cpp.

Used to remember the number of markers we publish so we can delete them later.

Definition at line 118 of file fast_plane_detector_node.cpp.

the plane

Definition at line 136 of file fast_plane_detector_node.cpp.

plane detection object

Definition at line 103 of file fast_plane_detector_node.cpp.

Publisher to Plane Parameters.

Definition at line 89 of file fast_plane_detector_node.cpp.

Publisher to Plane Parameters.

Definition at line 92 of file fast_plane_detector_node.cpp.

object for transforming from x,y,d space to x,y,z

Definition at line 109 of file fast_plane_detector_node.cpp.

Node handle in the private namespace.

Definition at line 69 of file fast_plane_detector_node.cpp.

The node handle.

Definition at line 67 of file fast_plane_detector_node.cpp.

Which direction along optical axis is pointing best towards up direction.

Definition at line 112 of file fast_plane_detector_node.cpp.


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


fast_plane_detection
Author(s): Jeannette Bohg
autogenerated on Tue Mar 5 16:04:18 2013