sac_model_normal_plane.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009 Radu Bogdan Rusu <rusu -=- cs.tum.edu>
00003  *
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 met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  *
00027  * $Id: sac_model_oriented_plane.cpp 10961 2009-02-11 00:20:50Z tfoote $
00028  *
00029  */
00030 
00033 #include <door_handle_detector/sample_consensus/sac_model_normal_plane.h>
00034 #include <door_handle_detector/geometry/angles.h>
00035 #include <door_handle_detector/geometry/point.h>
00036 #include <door_handle_detector/geometry/nearest.h>
00037 
00038 namespace sample_consensus
00039 {
00040   int get_channel_index(sensor_msgs::PointCloud *cloud, std::string name)
00041   {
00042     for (unsigned int i = 0; i < cloud->channels.size(); i++)
00043       if (cloud->channels[i].name.compare(name) == 0)
00044         return i;
00045     return -1;
00046 
00047   }
00048 
00050 
00057   void
00058     SACModelNormalPlane::selectWithinDistance (const std::vector<double> &model_coefficients, double threshold, std::vector<int> &inliers)
00059   {
00060     int nr_p = 0;
00061     double w = normal_distance_weight_;
00062 
00063     // Obtain the plane normal
00064     geometry_msgs::Point32 n;
00065     n.x = model_coefficients.at (0);
00066     n.y = model_coefficients.at (1);
00067     n.z = model_coefficients.at (2);
00068     double nw = model_coefficients.at (3);
00069 
00070     //ROS_INFO("coeff = (%.2f, %.2f, %.2f, %.2f)", n.x, n.y, n.z, nw);
00071 
00072     // check against template, if given
00073     if (eps_angle_ > 0.0)
00074       {
00075         double angle_diff = fabs(cloud_geometry::angles::getAngle3D (axis_, n));
00076         angle_diff = fmin(angle_diff, M_PI - angle_diff);
00077         if (angle_diff > eps_angle_)
00078           {
00079             inliers.resize (0);
00080             return;
00081           }
00082       }
00083     if (eps_dist_ > 0.0)
00084       {
00085         double d = -nw;
00086         if (fabs(d - dist_) > eps_dist_)
00087           {
00088             inliers.resize (0);
00089             return;
00090           }
00091       }
00092 
00093     // Get the point cloud's normal channels (fail if they don't exist)
00094     int nx_idx = get_channel_index(cloud_, "nx");
00095     int ny_idx = get_channel_index(cloud_, "ny");
00096     int nz_idx = get_channel_index(cloud_, "nz");
00097 
00098     //ROS_INFO("normal channels = (%d, %d, %d)", nx_idx, ny_idx, nz_idx);
00099 
00100     if (nx_idx < 0 || ny_idx < 0 || nz_idx < 0)
00101       {
00102         inliers.resize (0);
00103         return;
00104       }
00105 
00106     inliers.resize (indices_.size ());
00107     // Iterate through the 3d points and calculate the distances from them to the plane
00108     for (unsigned int i = 0; i < indices_.size (); i++)
00109     {
00110       // Calculate the Euclidean distance from the point to the plane normal as the dot product
00111       // D = (P-A).N/|N|
00112       geometry_msgs::Point32 p = cloud_->points[indices_.at (i)];
00113       double d_euclid = fabs(n.x*p.x + n.y*p.y + n.z*p.z + nw);
00114 
00115       // Calculate the angular distance between the point normal and the plane normal
00116       geometry_msgs::Point32 pn;
00117       pn.x = cloud_->channels[nx_idx].values[indices_.at (i)];
00118       pn.y = cloud_->channels[ny_idx].values[indices_.at (i)];
00119       pn.z = cloud_->channels[nz_idx].values[indices_.at (i)];
00120       double d_normal = fabs(cloud_geometry::angles::getAngle3D (pn, n));
00121       d_normal = fmin(d_normal, M_PI - d_normal);
00122 
00123       if (fabs (w*d_normal + (1-w)*d_euclid) < threshold)
00124       {
00125         //ROS_INFO("n = (%.2f, %.2f, %.2f), pn = (%.2f, %.2f, %.2f), d_normal = %.2f  -->  *** INLIER ***", n.x, n.y, n.z, pn.x, pn.y, pn.z, d_normal);
00126 
00127         // Returns the indices of the points whose distances are smaller than the threshold
00128         inliers[nr_p] = indices_[i];
00129         nr_p++;
00130       }
00131       //else
00132       //  ROS_INFO("n = (%.2f, %.2f, %.2f), pn = (%.2f, %.2f, %.2f), d_normal = %.2f", n.x, n.y, n.z, pn.x, pn.y, pn.z, d_normal);
00133     }
00134     inliers.resize (nr_p);
00135     return;
00136   }
00137 
00139 
00143   void
00144     SACModelNormalPlane::getDistancesToModel (const std::vector<double> &model_coefficients, std::vector<double> &distances)
00145   {
00146     double w = normal_distance_weight_;
00147 
00148     // Obtain the plane normal
00149     geometry_msgs::Point32 n;
00150     n.x = model_coefficients.at (0);
00151     n.y = model_coefficients.at (1);
00152     n.z = model_coefficients.at (2);
00153     double nw = model_coefficients.at (3);
00154 
00155     // check against template, if given
00156     if (eps_angle_ > 0.0)
00157       {
00158         double angle_diff = fabs(cloud_geometry::angles::getAngle3D (axis_, n));
00159         angle_diff = fmin(angle_diff, M_PI - angle_diff);
00160         if (angle_diff > eps_angle_)
00161           {
00162             distances.resize (0);
00163             return;
00164           }
00165       }
00166     if (eps_dist_ > 0.0)
00167       {
00168         double d = -nw;
00169         if (fabs(d - dist_) > eps_dist_)
00170           {
00171             distances.resize (0);
00172             return;
00173           }
00174       }
00175 
00176     // Get the point cloud's normal channels (fail if they don't exist)
00177     int nx_idx = get_channel_index(cloud_, "nx");
00178     int ny_idx = get_channel_index(cloud_, "ny");
00179     int nz_idx = get_channel_index(cloud_, "nz");
00180 
00181     //ROS_INFO("nx = %d, ny = %d, nz = %d", nx_idx, ny_idx, nz_idx);  //dbug
00182 
00183     if (nx_idx < 0 || ny_idx < 0 || nz_idx < 0)
00184       {
00185         distances.resize (0);
00186         return;
00187       }
00188 
00189     distances.resize (indices_.size ());
00190     // Iterate through the 3d points and calculate the distances from them to the plane
00191     for (unsigned int i = 0; i < indices_.size (); i++)
00192       {
00193         // Calculate the distance from the point to the plane normal as the dot product
00194         // D = (P-A).N/|N|
00195         geometry_msgs::Point32 p = cloud_->points[indices_.at (i)];
00196         double d_euclid = fabs(n.x*p.x + n.y*p.y + n.z*p.z + nw);
00197 
00198         // Calculate the angular distance between the point normal and the plane normal
00199         geometry_msgs::Point32 pn;
00200         pn.x = cloud_->channels[nx_idx].values[indices_.at (i)];
00201         pn.y = cloud_->channels[ny_idx].values[indices_.at (i)];
00202         pn.z = cloud_->channels[nz_idx].values[indices_.at (i)];
00203         double d_normal = fabs(cloud_geometry::angles::getAngle3D (pn, n));
00204         d_normal = fmin(d_normal, M_PI - d_normal);
00205 
00206         distances[i] = fabs (w*d_normal + (1-w)*d_euclid);
00207       }
00208 
00209     return;
00210   }
00211 
00212 }


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Wed Dec 11 2013 14:17:01