$search
00001 /* 00002 * Copyright (c) 2011, Jeannette Bohg and Mårten Björkman 00003 * ({bohg,celle}@csc.kth.se) 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are 00008 * met: 00009 * 00010 * 1.Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * 2.Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * 3.The name of Jeannette Bohg or Mårten Björkman may not be used to 00017 * endorse or promote products derived from this software without 00018 * specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 00023 * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 00024 * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 00025 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00026 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00027 * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 00028 * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00029 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00030 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00031 */ 00032 00033 #include <ros/ros.h> 00034 #include <std_msgs/String.h> 00035 00036 #include <fast_plane_detection/Plane.h> 00037 00038 #include <tf/transform_listener.h> 00039 00040 #include <stdio.h> 00041 00042 #define PI 3.1415926535897932384626433832795 00043 #define BUFSIZE 512 00044 00045 class PlaneDataDumper 00046 { 00047 00048 public: 00049 PlaneDataDumper( int buffer_size, int post_fix, int n_data_points = 500 ); 00050 ~PlaneDataDumper(); 00051 00052 void dumpData(); 00053 00054 private: 00055 00056 void dumpModes(); 00057 void dumpScatter(); 00058 00060 void planeCallback(const fast_plane_detection::Plane::ConstPtr& plane); 00061 00062 00063 void getGaussParameters(float &mean, 00064 float &var, 00065 int &norm, 00066 const std::vector<int> &angle_hist, 00067 float res, 00068 float min_val); 00069 00071 ros::NodeHandle root_nh_; 00073 ros::NodeHandle priv_nh_; 00074 00076 ros::Subscriber plane_sub_; 00077 std::string plane_topic_; 00078 00080 int buffer_size_; 00081 00083 int post_fix_; 00084 00086 int n_data_points_; 00087 00089 int n_current_; 00090 00092 tf::TransformListener listener_; 00093 tf::StampedTransform transform_; 00094 00095 std::string camera_frame_; 00096 std::string source_frame_; 00097 00099 int min_angle_, max_angle_; 00100 00102 float res_angle_; 00103 00105 int min_dist_, max_dist_; 00106 00108 float res_dist_; 00109 00111 std::vector<int> angle_hist_; 00112 00114 std::vector<int> dist_hist_; 00115 00117 std::vector<float> angles_; 00118 std::vector<float> mean_err_; 00119 std::vector<float> n_inliers_; 00120 00121 }; 00122 00123 PlaneDataDumper::PlaneDataDumper( int buffer_size, int post_fix, 00124 int n_data_points) 00125 : root_nh_("") 00126 , priv_nh_("~") 00127 , buffer_size_(buffer_size) 00128 , post_fix_(post_fix) 00129 , n_data_points_(n_data_points) 00130 , n_current_(0) 00131 { 00132 priv_nh_.param<std::string>("plane_topic", plane_topic_, 00133 "region_plane_msg"); 00134 00135 priv_nh_.param<std::string>("source_frame", source_frame_, 00136 "torso_lift_link"); 00137 00138 priv_nh_.param<std::string>("camera_frame", camera_frame_, 00139 "narrow_stereo_optical_frame"); 00140 00141 priv_nh_.param<int>("min_angle", min_angle_,post_fix-20); 00142 priv_nh_.param<int>("max_angle", max_angle_,post_fix+20); 00143 00144 priv_nh_.param<int>("min_dist", min_dist_,60); 00145 priv_nh_.param<int>("max_dist", max_dist_,80); 00146 00147 plane_sub_ = root_nh_.subscribe(plane_topic_, 00148 buffer_size_, 00149 &PlaneDataDumper::planeCallback, 00150 this); 00151 00152 res_angle_ = 0.5; 00153 res_dist_ = 0.1; 00154 00155 int angle_size = (max_angle_ - min_angle_)/res_angle_; 00156 int dist_size = (max_dist_ - min_dist_)/res_dist_; 00157 00158 ROS_INFO("Angle_size %i \t Dist_size %i\n", angle_size, dist_size); 00159 00160 angle_hist_.resize(angle_size,0); 00161 dist_hist_.resize(dist_size,0); 00162 00163 angles_.resize(n_data_points_,-1); 00164 mean_err_.resize(n_data_points_,-1); 00165 n_inliers_.resize(n_data_points_,-1); 00166 } 00167 00168 PlaneDataDumper::~PlaneDataDumper() 00169 { 00170 } 00171 00172 void PlaneDataDumper::planeCallback(const fast_plane_detection::Plane::ConstPtr& plane) 00173 { 00174 00175 if(plane->result==fast_plane_detection::Plane::FEW_INLIERS || 00176 plane->result==fast_plane_detection::Plane::NO_PLANE){ 00177 ROS_WARN("OUTLIER\n"); 00178 return; 00179 } 00180 00181 if(n_current_>n_data_points_){ 00182 ROS_WARN("Neccessary data points collected!"); 00183 return; 00184 } 00185 00186 00187 // Transform into torso_lift_link 00188 // What is the current transform from camera to source 00189 try { 00190 listener_.lookupTransform(source_frame_, 00191 camera_frame_, 00192 ros::Time(0), 00193 transform_); 00194 } catch (tf::TransformException ex) { 00195 ROS_ERROR("%s", ex.what()); 00196 } 00197 // Plane Point (transformed to source frame) 00198 btVector3 point1(plane->pose.pose.position.x, 00199 plane->pose.pose.position.y, 00200 plane->pose.pose.position.z); 00201 point1 = transform_.getBasis() * point1 + 00202 transform_.getOrigin(); 00203 geometry_msgs::PointStamped plane_point; 00204 plane_point.header.frame_id = source_frame_; 00205 plane_point.header.stamp = ros::Time::now(); 00206 plane_point.point.x = point1.x(); 00207 plane_point.point.y = point1.y(); 00208 plane_point.point.z = point1.z(); 00209 // Plane normal (transformed to source frame) 00210 btVector3 point2(plane->normal.vector.x, 00211 plane->normal.vector.y, 00212 plane->normal.vector.z); 00213 point2 = transform_.getBasis() * point2; 00214 /* 00215 ROS_INFO("Normal of plane in camera_frame: %f %f %f", 00216 plane->normal.vector.x, plane->normal.vector.y, 00217 plane->normal.vector.z); 00218 */ 00219 geometry_msgs::Vector3Stamped plane_normal; 00220 plane_normal.header.frame_id = source_frame_; 00221 plane_normal.header.stamp = ros::Time::now(); 00222 plane_normal.vector.x = point2.x(); 00223 plane_normal.vector.y = point2.y(); 00224 plane_normal.vector.z = point2.z(); 00225 /* 00226 ROS_INFO("Normal of plane in source_frame: %f %f %f", 00227 plane_normal.vector.x, plane_normal.vector.y, 00228 plane_normal.vector.z); 00229 */ 00230 00231 float angle = (atan2(plane_normal.vector.y,plane_normal.vector.x) 00232 /PI*180.0f); 00233 00234 ROS_INFO("Angle %f\n", angle); 00235 00236 int cell; 00237 if(angle>min_angle_ && angle<max_angle_){ 00238 cell = (angle - min_angle_)/res_angle_; 00239 angle_hist_[cell]++; 00240 } 00241 float length = std::sqrt(plane_point.point.x * plane_point.point.x + 00242 plane_point.point.y * plane_point.point.y + 00243 plane_point.point.z * plane_point.point.z) 00244 * 100; 00245 ROS_INFO("Length %f\n", length); 00246 00247 if(length>min_dist_ && length<max_dist_){ 00248 cell = (int)((float)(length-min_dist_)/res_dist_); 00249 dist_hist_[cell]++; 00250 } 00251 00252 angles_[n_current_] = angle; 00253 mean_err_[n_current_] = plane->error; 00254 n_inliers_[n_current_] = plane->percentage_inliers; 00255 00256 n_current_++; 00257 } 00258 00259 void PlaneDataDumper::getGaussParameters(float &mean, 00260 float &var, 00261 int &norm, 00262 const std::vector<int> &hist, 00263 float res, 00264 float min_val) 00265 { 00266 norm = 0; 00267 mean = 0; 00268 for(size_t i = 0; i<hist.size(); ++i){ 00269 norm +=hist[i]; 00270 mean +=hist[i]*i; 00271 } 00272 00273 mean /= (float)norm; 00274 mean *= res; 00275 mean += min_val; 00276 00277 00278 var = 0; 00279 for(size_t i = 0; i<hist.size(); ++i){ 00280 float trans = i*res + min_val; 00281 var += (trans-mean) * (trans-mean) * hist[i]/(float)norm; 00282 } 00283 00284 //ROS_INFO("Mean %f and Variance %f\n", mean, var); 00285 00286 } 00287 00288 void PlaneDataDumper::dumpData() 00289 { 00290 dumpModes(); 00291 dumpScatter(); 00292 } 00293 00294 void PlaneDataDumper::dumpScatter() 00295 { 00296 char name[BUFSIZE]; 00297 sprintf(name, "../eval/scatter_%i.txt", post_fix_); 00298 FILE* fp = fopen(name, "w"); 00299 00300 for(size_t i = 0; i<angles_.size(); ++i){ 00301 if(angles_[i]!=-1) 00302 fprintf(fp, "%f \t %f \t %f\n", 00303 angles_[i], mean_err_[i], n_inliers_[i]); 00304 else 00305 break; 00306 } 00307 fclose(fp); 00308 } 00309 00310 void PlaneDataDumper::dumpModes() 00311 { 00312 00313 int norm_angle; 00314 float mean_angle, var_angle; 00315 getGaussParameters(mean_angle, var_angle, 00316 norm_angle, angle_hist_, 00317 res_angle_, 00318 min_angle_); 00319 00320 00321 int norm_dist; 00322 float mean_dist, var_dist; 00323 getGaussParameters(mean_dist, var_dist, 00324 norm_dist, dist_hist_, 00325 res_dist_, 00326 min_dist_); 00327 00328 printf("Number of Angle Measurements %i\n", norm_angle); 00329 printf("Mean Angle %f\n", mean_angle); 00330 printf("Variance Angle %f\n", var_angle); 00331 00332 00333 char name[BUFSIZE]; 00334 sprintf(name, "../eval/angle_hist_%i.txt", post_fix_); 00335 FILE* fp = fopen(name, "w"); 00336 00337 for(size_t i = 0; i<angle_hist_.size(); ++i){ 00338 float angle = (float)i*res_angle_+min_angle_; 00339 float val = (float)angle_hist_[i]/(float)norm_angle; 00340 fprintf(fp, "%f \t %f\n", angle, val); 00341 } 00342 fclose(fp); 00343 00344 printf("Number of Dist Measurements %i\n", norm_dist); 00345 printf("Mean Distance %f\n", mean_dist); 00346 printf("Variance Distance %f\n", var_dist); 00347 00348 sprintf(name, "../eval/dist_hist_%i.txt", post_fix_); 00349 FILE* fp2 = fopen(name, "w"); 00350 00351 for(size_t i = 0; i<dist_hist_.size(); ++i) { 00352 float dist = (float)i*res_dist_+min_dist_; 00353 float val = (float)dist_hist_[i]/(float)norm_dist; 00354 fprintf(fp2, "%f \t %f\n", dist, val); 00355 } 00356 fclose(fp2); 00357 00358 sprintf(name, "../eval/mean_angle_%i.tex", post_fix_); 00359 FILE* fp3 = fopen(name, "w"); 00360 fprintf(fp3, "\\def \\meanAngle {%f}\n", mean_angle); 00361 fclose(fp3); 00362 00363 sprintf(name, "../eval/std_angle_%i.tex", post_fix_); 00364 FILE* fp4 = fopen(name, "w"); 00365 fprintf(fp4, "\\def \\stdAngle {%f}\n", std::sqrt(var_angle)); 00366 fclose(fp4); 00367 00368 sprintf(name, "../eval/mean_dist_%i.tex", post_fix_); 00369 FILE* fp5 = fopen( name, "w"); 00370 fprintf(fp5, "\\def \\meanDist {%f}\n", mean_dist); 00371 fclose(fp5); 00372 00373 sprintf(name, "../eval/std_dist_%i.tex", post_fix_); 00374 FILE* fp6 = fopen( name, "w"); 00375 fprintf(fp6, "\\def \\stdDist {%f}\n", std::sqrt(var_dist)); 00376 fclose(fp6); 00377 00378 } 00379 00380 int main(int argc, char **argv) 00381 { 00382 ros::init(argc, argv, "plane_data_dumper"); 00383 00384 if(argc<2){ 00385 std::cout << "Usage " << argv[0] << " postfix [n_data_points]" 00386 << std::endl; 00387 return -1; 00388 } 00389 00390 00391 int buffer_size_ = 1; 00392 PlaneDataDumper* node_; 00393 if(argc==2) 00394 node_ = new PlaneDataDumper(buffer_size_, atoi(argv[1])); 00395 else if(argc==3) 00396 node_ = new PlaneDataDumper(buffer_size_, atoi(argv[1]), atoi(argv[2])); 00397 ros::spin(); 00398 00399 node_->dumpData(); 00400 00401 return 0; 00402 }