$search
00001 /* 00002 * Copyright (c) 2011, Jeannette Bohg and Mårten Björkman ({bohg,celle}@csc.kth.se) 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are 00007 * met: 00008 * 00009 * 1.Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * 2.Redistributions in binary form must reproduce the above 00012 * copyright notice, this list of conditions and the following 00013 * disclaimer in the documentation and/or other materials provided 00014 * with the distribution. 00015 * 3.The name of Jeannette Bohg or Mårten Björkman may not be used to endorse or 00016 * promote products derived from this software without specific 00017 * prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00020 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00021 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 00022 * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 00023 * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 00024 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00025 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00026 * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 00027 * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00028 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00029 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00030 */ 00031 00032 #ifndef PLANE_DETECTION 00033 #define PLANE_DETECTION 00034 00035 #include <stereo_msgs/DisparityImage.h> 00036 #include <sensor_msgs/Image.h> 00037 00038 namespace fast_plane_detection { 00039 00040 class PlaneDetection { 00041 00042 public: 00043 PlaneDetection( int drange, int w, int h, 00044 bool find_table, std_msgs::Header img_header, 00045 bool search_y = true); 00046 ~PlaneDetection(); 00047 00048 void Update(const stereo_msgs::DisparityImage::ConstPtr& 00049 disparity_image); 00050 00051 void GetPlaneParameters( float &alpha, float &beta, float &d, 00052 int &min_x, int &max_x, 00053 int &min_y, int &max_y); 00054 float GetSpreadX(); 00055 float GetSpreadY(); 00056 void GetLabels(sensor_msgs::Image &image); 00057 void GetHistY(sensor_msgs::Image &image, 00058 float &beta, float &disp); 00059 void GetHistX(sensor_msgs::Image &image, 00060 float &beta, float &disp); 00061 void GetSumOfSquaredError(float &error); 00062 void GetNInliers(int &n_inliers); 00063 void GetNDisp(int &n_disp); 00064 void GetMeanSquaredError(float &mean_error); 00065 00066 private: 00067 00068 void Update_Y( const stereo_msgs::DisparityImage::ConstPtr& 00069 disparity_image ); 00070 void Update_X( const stereo_msgs::DisparityImage::ConstPtr& 00071 disparity_image ); 00072 00074 sensor_msgs::Image labels_; 00075 00077 sensor_msgs::Image hist_y_; 00078 float tmp_beta_; 00079 float tmp_disp_; 00080 00082 sensor_msgs::Image hist_x_; 00083 float tmp_beta_x_; 00084 float tmp_disp_x_; 00085 00087 int drange_; 00088 00090 int width_, height_; 00091 00093 int min_x_; int max_x_; 00094 int min_y_; int max_y_; 00095 00098 bool find_table_; 00099 float min_beta_; 00100 00102 bool search_y_; 00103 00105 float alpha_; 00106 float beta_; 00107 float disp_; 00108 00110 float spread_d_y_; 00111 float spread_d_x_; 00112 00114 float err_; 00115 00117 int n_inliers_; 00118 00120 int n_disps_; 00121 00122 }; 00123 00124 } // fast_plane_detection 00125 00126 #endif //PLANE_DETECTION