$search

fast_plane_detection::PlaneDetection Class Reference

#include <plane_detection.h>

List of all members.

Public Member Functions

void GetHistX (sensor_msgs::Image &image, float &beta, float &disp)
void GetHistY (sensor_msgs::Image &image, float &beta, float &disp)
void GetLabels (sensor_msgs::Image &image)
void GetMeanSquaredError (float &mean_error)
void GetNDisp (int &n_disp)
void GetNInliers (int &n_inliers)
void GetPlaneParameters (float &alpha, float &beta, float &d, int &min_x, int &max_x, int &min_y, int &max_y)
float GetSpreadX ()
float GetSpreadY ()
void GetSumOfSquaredError (float &error)
 PlaneDetection (int drange, int w, int h, bool find_table, std_msgs::Header img_header, bool search_y=true)
void Update (const stereo_msgs::DisparityImage::ConstPtr &disparity_image)
 ~PlaneDetection ()

Private Member Functions

void Update_X (const stereo_msgs::DisparityImage::ConstPtr &disparity_image)
void Update_Y (const stereo_msgs::DisparityImage::ConstPtr &disparity_image)

Private Attributes

float alpha_
 plane parameters (alpha_*x + beta_*y + disp_ = d)
float beta_
float disp_
int drange_
 Disparity Range.
float err_
 sum of squared error
bool find_table_
int height_
sensor_msgs::Image hist_x_
 Histogram Image X.
sensor_msgs::Image hist_y_
 Histogram Image Y.
sensor_msgs::Image labels_
 Labeled Image.
int max_x_
int max_y_
float min_beta_
int min_x_
 limits of visible plane
int min_y_
int n_disps_
 number of valid disparities
int n_inliers_
 number of inliers
bool search_y_
 Search over X or Y.
float spread_d_x_
float spread_d_y_
 mean squared error
float tmp_beta_
float tmp_beta_x_
float tmp_disp_
float tmp_disp_x_
int width_
 image dimensions

Detailed Description

Definition at line 40 of file plane_detection.h.


Constructor & Destructor Documentation

fast_plane_detection::PlaneDetection::PlaneDetection ( int  drange,
int  w,
int  h,
bool  find_table,
std_msgs::Header  img_header,
bool  search_y = true 
)

Definition at line 40 of file plane_detection.cpp.

fast_plane_detection::PlaneDetection::~PlaneDetection (  ) 

Definition at line 90 of file plane_detection.cpp.


Member Function Documentation

void fast_plane_detection::PlaneDetection::GetHistX ( sensor_msgs::Image image,
float &  beta,
float &  disp 
)

Definition at line 563 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetHistY ( sensor_msgs::Image image,
float &  beta,
float &  disp 
)

Definition at line 555 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetLabels ( sensor_msgs::Image image  ) 

Definition at line 550 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetMeanSquaredError ( float &  mean_error  ) 

Definition at line 586 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetNDisp ( int &  n_disp  ) 

Definition at line 581 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetNInliers ( int &  n_inliers  ) 

Definition at line 576 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetPlaneParameters ( float &  alpha,
float &  beta,
float &  d,
int &  min_x,
int &  max_x,
int &  min_y,
int &  max_y 
)

Definition at line 523 of file plane_detection.cpp.

float fast_plane_detection::PlaneDetection::GetSpreadX (  ) 

Definition at line 540 of file plane_detection.cpp.

float fast_plane_detection::PlaneDetection::GetSpreadY (  ) 

Definition at line 545 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::GetSumOfSquaredError ( float &  error  ) 

Definition at line 571 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::Update ( const stereo_msgs::DisparityImage::ConstPtr disparity_image  ) 

Definition at line 93 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::Update_X ( const stereo_msgs::DisparityImage::ConstPtr disparity_image  )  [private]

Definition at line 311 of file plane_detection.cpp.

void fast_plane_detection::PlaneDetection::Update_Y ( const stereo_msgs::DisparityImage::ConstPtr disparity_image  )  [private]

Definition at line 102 of file plane_detection.cpp.


Member Data Documentation

plane parameters (alpha_*x + beta_*y + disp_ = d)

Definition at line 105 of file plane_detection.h.

Definition at line 106 of file plane_detection.h.

Definition at line 107 of file plane_detection.h.

Disparity Range.

Definition at line 87 of file plane_detection.h.

sum of squared error

Definition at line 114 of file plane_detection.h.

Minimum beta of plane parameters (for restricting plane orientation)

Definition at line 98 of file plane_detection.h.

Definition at line 90 of file plane_detection.h.

Histogram Image X.

Definition at line 82 of file plane_detection.h.

Histogram Image Y.

Definition at line 77 of file plane_detection.h.

Labeled Image.

Definition at line 74 of file plane_detection.h.

Definition at line 93 of file plane_detection.h.

Definition at line 94 of file plane_detection.h.

Definition at line 99 of file plane_detection.h.

limits of visible plane

Definition at line 93 of file plane_detection.h.

Definition at line 94 of file plane_detection.h.

number of valid disparities

Definition at line 120 of file plane_detection.h.

number of inliers

Definition at line 117 of file plane_detection.h.

Search over X or Y.

Definition at line 102 of file plane_detection.h.

Definition at line 111 of file plane_detection.h.

mean squared error

Definition at line 110 of file plane_detection.h.

Definition at line 78 of file plane_detection.h.

Definition at line 83 of file plane_detection.h.

Definition at line 79 of file plane_detection.h.

Definition at line 84 of file plane_detection.h.

image dimensions

Definition at line 90 of file plane_detection.h.


The documentation for this class was generated from the following files:
 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:19 2013