#include <plane_detection.h>
Public Member Functions | |
| void | GetLabels (sensor_msgs::Image &image) |
| void | GetMeanSquaredError (float &mean_error) |
| 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) |
| void | GetSumOfSquaredError (float &error) |
| PlaneDetection (int drange, int w, int h, bool find_table, std_msgs::Header img_header) | |
| void | Update (const stereo_msgs::DisparityImage::ConstPtr &disparity_image) |
| ~PlaneDetection () | |
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 | labels_ |
| Labeled Image. | |
| int | max_x_ |
| int | max_y_ |
| float | min_beta_ |
| int | min_x_ |
| limits of visible plane | |
| int | min_y_ |
| int | n_inliers_ |
| number of inliers | |
| float | spread_d_ |
| mean squared error | |
| int | width_ |
| image dimensions | |
Definition at line 38 of file plane_detection.h.
| fast_plane_detection::PlaneDetection::PlaneDetection | ( | int | drange, | |
| int | w, | |||
| int | h, | |||
| bool | find_table, | |||
| std_msgs::Header | img_header | |||
| ) |
Definition at line 37 of file plane_detection.cpp.
| fast_plane_detection::PlaneDetection::~PlaneDetection | ( | ) |
Definition at line 64 of file plane_detection.cpp.
| void fast_plane_detection::PlaneDetection::GetLabels | ( | sensor_msgs::Image & | image | ) |
Definition at line 257 of file plane_detection.cpp.
| void fast_plane_detection::PlaneDetection::GetMeanSquaredError | ( | float & | mean_error | ) |
Definition at line 272 of file plane_detection.cpp.
| void fast_plane_detection::PlaneDetection::GetNInliers | ( | int & | n_inliers | ) |
Definition at line 267 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 240 of file plane_detection.cpp.
| void fast_plane_detection::PlaneDetection::GetSumOfSquaredError | ( | float & | error | ) |
Definition at line 262 of file plane_detection.cpp.
| void fast_plane_detection::PlaneDetection::Update | ( | const stereo_msgs::DisparityImage::ConstPtr & | disparity_image | ) |
Definition at line 67 of file plane_detection.cpp.
float fast_plane_detection::PlaneDetection::alpha_ [private] |
plane parameters (alpha_*x + beta_*y + disp_ = d)
Definition at line 76 of file plane_detection.h.
float fast_plane_detection::PlaneDetection::beta_ [private] |
Definition at line 77 of file plane_detection.h.
float fast_plane_detection::PlaneDetection::disp_ [private] |
Definition at line 78 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::drange_ [private] |
Disparity Range.
Definition at line 61 of file plane_detection.h.
float fast_plane_detection::PlaneDetection::err_ [private] |
sum of squared error
Definition at line 84 of file plane_detection.h.
bool fast_plane_detection::PlaneDetection::find_table_ [private] |
Minimum beta of plane parameters (for restricting plane orientation)
Definition at line 72 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::height_ [private] |
Definition at line 64 of file plane_detection.h.
sensor_msgs::Image fast_plane_detection::PlaneDetection::labels_ [private] |
Labeled Image.
Definition at line 58 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::max_x_ [private] |
Definition at line 67 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::max_y_ [private] |
Definition at line 68 of file plane_detection.h.
float fast_plane_detection::PlaneDetection::min_beta_ [private] |
Definition at line 73 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::min_x_ [private] |
limits of visible plane
Definition at line 67 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::min_y_ [private] |
Definition at line 68 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::n_inliers_ [private] |
number of inliers
Definition at line 87 of file plane_detection.h.
float fast_plane_detection::PlaneDetection::spread_d_ [private] |
mean squared error
Definition at line 81 of file plane_detection.h.
int fast_plane_detection::PlaneDetection::width_ [private] |
image dimensions
Definition at line 64 of file plane_detection.h.