box_fit_algo.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Dejan Pangercic <dejan.pangercic@cs.tum.edu>,
00003  Zoltan-Csaba Marton <marton@cs.tum.edu>, Nico Blodow <blodow@cs.tum.edu>
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  *     * Neither the name of Willow Garage, Inc. nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  */
00030 
00032 
00033 #include <pcl/features/feature.h>
00034 #include <pcl/io/io.h>
00035 
00036 #include <stdlib.h>
00037 
00038 #include <vector>
00039 #include <iostream>
00040 
00041 
00042 // kd-tree, getPointCloud and computeCentroid
00043 //#include <point_cloud_mapping/kdtree/kdtree_ann.h>
00044 //#include <point_cloud_mapping/geometry/point.h>
00045 //#include <point_cloud_mapping/geometry/nearest.h>
00046 
00047 //ros
00048 #include <sensor_msgs/PointCloud2.h>
00049 //#include <geometry_msgs/PointStamped.h>
00050 #include <geometry_msgs/Point32.h>
00051 #include <ros/ros.h>
00052 
00053 //cloud_algos
00054 #include <pcl_cloud_algos/box_fit_algo.h>
00055 
00056 //bullet TODO: maybe replace that function with one from Eigen
00057 #include <tf/tf.h>
00058 
00059 // Eigen
00060 #include <Eigen/Core>
00061 
00062 #include <angles/angles.h>
00063 
00064 #include <triangle_mesh_msgs/TriangleMesh.h>
00065 
00066 
00067 using namespace std;
00068 using namespace pcl_cloud_algos;
00069 
00070 void BoxEstimation::init (ros::NodeHandle& nh)
00071 {
00072   nh_ = nh;
00073   nh_.param("output_box_topic", output_box_topic_, output_box_topic_);
00074   marker_pub_ = nh_.advertise<visualization_msgs::Marker>(output_box_topic_, 0 );
00075   inliers_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("inliers", 0 );
00076   outliers_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("outliers", 0 );
00077   contained_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("contained", 0 );
00078   coeff_.resize(15);
00079   r_ = g_ = 0.0;
00080   b_ = 1.0;
00081   cloud_ = boost::make_shared<pcl::PointCloud<pcl::PointXYZINormal> > ();
00082 }
00083 
00084 void BoxEstimation::pre  ()
00085 {
00086   nh_.param("output_box_topic", output_box_topic_, output_box_topic_);
00087   marker_pub_ = nh_.advertise<visualization_msgs::Marker>(output_box_topic_, 0 );
00088   nh_.param("threshold_in", threshold_in_, threshold_in_);
00089   nh_.param("threshold_out", threshold_out_, threshold_out_);
00090   nh_.param("publish_marker", publish_marker_, publish_marker_);
00091 }
00092 
00093 void BoxEstimation::post ()
00094 {
00095 }
00096 
00097 std::vector<std::string> BoxEstimation::requires ()
00098 {
00099   std::vector<std::string> ret;
00100   ret.push_back (std::string("index"));
00101   return ret;
00102 }
00103 
00104 std::vector<std::string> BoxEstimation::provides ()
00105 {
00106   return std::vector<std::string>();
00107 }
00108 
00109 std::string BoxEstimation::process (const boost::shared_ptr<const InputType> input)
00110 {
00111   frame_id_ = input->header.frame_id;
00112   //converting to pcl format
00113   pcl::fromROSMsg(*input, *cloud_);
00114 
00115   if (verbosity_level_ > 0) ROS_INFO ("[BoxEstimation] PointCloud message received on %s with %d points", default_input_topic().c_str (), (int)cloud_->points.size ());
00116 
00117   // Compute model coefficients
00118   bool model_found = find_model (cloud_, coeff_);
00119 
00120   // Check if a valid model was found
00121   if (!model_found)
00122   {
00123     output_valid_ = false;
00124     return std::string ("no model found");
00125   }
00126   else
00127   {
00128     // Create mesh as output
00129     triangulate_box (cloud_, coeff_);
00130 
00131     // Publish fitted box on marker topic
00132     if (verbosity_level_ > 0) ROS_INFO ("[BoxEstimation] Publishing box marker on topic %s.", nh_.resolveName (output_box_topic_).c_str ());
00133     if (publish_marker_)
00134       publish_marker (cloud_, coeff_);
00135     else
00136       computeMarker (cloud_, coeff_);
00137 
00138     // Get which points verify the model and which don't
00139     // cloud_ = input;
00140     computeInAndOutliers (cloud_, coeff_, threshold_in_, threshold_out_);
00141     inliers_pub_.publish (getInliers ());
00142     outliers_pub_.publish (getOutliers ());
00143     contained_pub_.publish (getContained ());
00144 
00145     output_valid_ = true;
00146     return std::string ("ok");
00147   }
00148 }
00149 
00150 boost::shared_ptr<const BoxEstimation::OutputType> BoxEstimation::output ()
00151 {
00152   return mesh_;
00153 };
00154 
00155 boost::shared_ptr<sensor_msgs::PointCloud2> BoxEstimation::getOutliers ()
00156 {
00157   boost::shared_ptr<pcl::PointCloud<pcl::PointXYZINormal> > ret (new pcl::PointCloud<pcl::PointXYZINormal>);
00158   boost::shared_ptr<sensor_msgs::PointCloud2> ret_msg (new sensor_msgs::PointCloud2);
00159   //ROS_INFO("created PointCloud object: 0x%x", (void*) ret.get()); - ZOLI COMMENTED THIS TO GET RID OF WARNING, SUPPOSING WAS ONLY DEBUG :)
00160 
00161   //ret->header = cloud_->header;
00162   //int channel_index = getChannelIndex (cloud_, "index");
00163   //int channel_line = getChannelIndex (cloud_, "line");
00164   //if (channel_line != -1)
00165   //{
00166   //  ret->channels.resize(2);
00167   //  ret->channels[1].name = cloud_->channels[channel_line].name;
00168   //  ret->channels[1].values.resize(outliers_.size());
00169   //  ret->channels[0].name = cloud_->channels[channel_index].name;
00170   //  ret->channels[0].values.resize(outliers_.size());
00171   //}
00172   //else if (channel_index != -1)
00173   //{
00174   //  ret->channels.resize(1);
00175   //  ret->channels[0].name = cloud_->channels[channel_index].name;
00176   //  ret->channels[0].values.resize(outliers_.size());
00177   //}
00178 
00179   ret->points.resize(outliers_.size());
00180   for (unsigned int i = 0; i < outliers_.size (); i++)
00181   {
00182     ret->points.at(i) = cloud_->points.at (outliers_.at (i));
00183     //if (channel_index != -1)
00184     //  ret->channels[0].values.at(i) = cloud_->channels[channel_index].values.at (outliers_.at (i));
00185     //if (channel_line != -1)
00186     //  ret->channels[1].values.at(i) = cloud_->channels[channel_line].values.at (outliers_.at (i));
00187   }
00188   pcl::toROSMsg(*ret, *ret_msg);
00189   ret_msg->header.frame_id = frame_id_;
00190   ret_msg->header.stamp = ros::Time::now();
00191   return ret_msg;
00192 }
00193 
00194 boost::shared_ptr<sensor_msgs::PointCloud2> BoxEstimation::getInliers ()
00195 {
00196   boost::shared_ptr<pcl::PointCloud<pcl::PointXYZINormal> > ret (new pcl::PointCloud<pcl::PointXYZINormal> ());
00197   boost::shared_ptr<sensor_msgs::PointCloud2> ret_msg (new sensor_msgs::PointCloud2);
00198   pcl::copyPointCloud (*cloud_, inliers_, *ret);
00199   //ret->points.reserve (inliers_.size ());
00200   //ret->header = cloud_->header;
00201   //for (unsigned int i = 0; i < inliers_.size (); i++)
00202   //  ret->points.push_back (cloud_->points.at (inliers_.at (i)));
00203   pcl::toROSMsg(*ret, *ret_msg);
00204   ret_msg->header.frame_id = frame_id_;
00205   ret_msg->header.stamp = ros::Time::now();
00206   return ret_msg;
00207 }
00208 
00209 boost::shared_ptr<sensor_msgs::PointCloud2> BoxEstimation::getContained ()
00210 {
00211   boost::shared_ptr<pcl::PointCloud<pcl::PointXYZINormal> > ret (new pcl::PointCloud<pcl::PointXYZINormal> ());
00212   boost::shared_ptr<sensor_msgs::PointCloud2> ret_msg (new sensor_msgs::PointCloud2);
00213   pcl::copyPointCloud (*cloud_, contained_, *ret);
00214   //ret->points.reserve (contained_.size ());
00215   //ret->header = cloud_->header;
00216   //for (unsigned int i = 0; i < contained_.size (); i++)
00217   //  ret->points.push_back (cloud_->points.at (contained_.at (i)));
00218   pcl::toROSMsg(*ret, *ret_msg);
00219   ret_msg->header.frame_id = frame_id_;
00220   ret_msg->header.stamp = ros::Time::now();
00221   return ret_msg;
00222 }
00223 
00224 boost::shared_ptr<pcl::PointCloud <pcl::PointXYZINormal> > BoxEstimation::getThresholdedInliers (double eps_angle)
00225 {
00226   //int nxIdx = getChannelIndex(cloud_, "nx");
00227   //if (nxIdx == -1)
00228   //  return getInliers ();
00229   //else
00230   //{
00231     Eigen::Matrix3d axes = Eigen::Matrix3d::Map(&coeff_[6]).transpose ();
00232     //Eigen::Matrix3f axes = Eigen::Matrix3d::Map(&coeff_[6]).cast<float> ().transpose ();
00233     boost::shared_ptr<pcl::PointCloud<pcl::PointXYZINormal> > ret (new pcl::PointCloud<pcl::PointXYZINormal> ());
00234     ret->points.reserve (inliers_.size ());
00235     ret->header = cloud_->header;
00236     for (unsigned int i = 0; i < inliers_.size (); i++)
00237     {
00238       Eigen::Vector3d normal (cloud_->points.at (inliers_.at(i)).normal[0],
00239                               cloud_->points.at (inliers_.at(i)).normal[1],
00240                               cloud_->points.at (inliers_.at(i)).normal[2]);
00241 
00242       // TODO: include top inliers to cylinders!
00243       for (int d = 0; d < 3; d++)
00244       {
00245         double cosine = fabs (normal.dot (axes.row(d)));
00246         if (cosine > 1) cosine = 1;
00247         if (cosine < -1) cosine = -1;
00248         if (acos (cosine) < eps_angle)
00249         {
00250           ret->points.push_back (cloud_->points.at (inliers_.at (i)));
00251           break;
00252         }
00253       }
00254     }
00255     return ret;
00256   //}
00257 }
00258 
00259 void BoxEstimation::computeInAndOutliers (boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZINormal> > cloud, std::vector<double> coeff, double threshold_in, double threshold_out)
00260 {
00261   //Eigen::Matrix3f axes = Eigen::Matrix3d::Map(&coeff[6]).cast<float> ().transpose ();
00262   Eigen::Matrix3d axes = Eigen::Matrix3d::Map(&coeff[6]).transpose ();
00263   //std::cerr << "the 3 axes:\n" << axes << std::endl;
00264   //std::cerr << "threshold: " << threshold << std::endl;
00265 
00266   // get inliers and outliers
00267   inliers_.resize (0);
00268   outliers_.resize (0);
00269   contained_.resize (0);
00270   for (unsigned i = 0; i < cloud->points.size (); i++)
00271   {
00272     // compute point-center
00273     Eigen::Vector3d centered (cloud->points[i].x - coeff[0], cloud->points[i].y - coeff[1], cloud->points[i].z - coeff[2]);
00274     // project (point-center) on axes and check if inside or outside the +/- dimensions
00275     bool inlier = false;
00276     bool outlier = false;
00277     for (int d = 0; d < 3; d++)
00278     {
00279       double dist = fabs (centered.dot (axes.row(d)));
00280       if (dist > coeff[3+d]/2 + threshold_out)
00281       {
00282         outlier = true;
00283         break;
00284       }
00285       else if (fabs (dist - coeff[3+d]/2) <= threshold_in)
00286       {
00287         inlier = true;
00288         break;
00289       }
00290     }
00291     if (inlier)
00292       inliers_.push_back(i);
00293     else if (outlier)
00294       outliers_.push_back(i);
00295     else
00296       contained_.push_back(i);
00297   }
00298   if (verbosity_level_ > 0) ROS_INFO("[BoxEstimation] %ld points verify model, %ld are outside of it, and %ld are contained in it", inliers_.size(), outliers_.size(), contained_.size());
00299 }
00300 
00302 
00305 bool BoxEstimation::find_model (boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZINormal> > cloud, std::vector<double> &coeff)
00306 {
00307   //Eigen::Vector4f centroid;
00308   //pcl::compute3DCentroid (*cloud, centroid);
00309   //coeff[0] = box_centroid_.x;
00310   //coeff[1] = box_centroid_.y;
00311   //coeff[2] = box_centroid_.z;
00315   //std::vector<const geometry_msgs::Point32*> interest_pts;
00316   //interest_pts.reserve(cloud->points.size());
00318   //for (size_t i = 0 ; i < cloud->points.size() ; i++)
00319   //{
00320   //  interest_pts.push_back(&(cloud->points[i]));
00321   //}
00322 
00323   //cloud_kdtree::KdTreeANN data_kdtree(*cloud);
00324 
00331   //double r = 0.1;
00332   //SpectralAnalysis sa(r);
00333   //BoundingBoxSpectral bbox_spectral(r, sa);
00334   //OrientationTangent o_tangent(1, 0, 0, sa);
00337   //vector<Descriptor3D*> descriptors_3d;
00342   //descriptors_3d.push_back(&o_tangent);
00344   //descriptors_3d.push_back(&bbox_spectral);
00345 
00351   //unsigned int nbr_descriptors = descriptors_3d.size();
00352   //vector<std::vector<std::vector<float> > > all_descriptor_results(nbr_descriptors);
00353   //for (unsigned int i = 0 ; i < nbr_descriptors ; i++)
00354   //{
00355   //  descriptors_3d[i]->compute(*cloud, data_kdtree, interest_pts, all_descriptor_results[i]);
00356   //}
00357 
00358   //std::vector<float>& ot = all_descriptor_results[0][0];
00359   //if (verbosity_level_ > 1) cout << "Orientation tangent size: " <<  ot.size() << endl;
00360   //for (size_t i = 0 ; i < ot.size() ; i++)
00361   //  if (verbosity_level_ > 1) cerr << "Orientation tangent value(s): " << ot[i] << endl;
00362 
00365   //std::vector<float>& pt0_bbox_features = all_descriptor_results[1][0];
00366   //if (verbosity_level_ > 1) cout << "Bounding box features size: " <<  pt0_bbox_features.size() << endl;
00367   //for (size_t i = 0 ; i < pt0_bbox_features.size() ; i++)
00368   //{
00369   //  if (i < 12)
00370   //  {
00371   //    coeff[i+3] = pt0_bbox_features[i];
00372   //  }
00373   //  else
00374   //    if (verbosity_level_ > -1) ROS_WARN("[BoxEstimation] Box dimensions bigger than 3 - unusual");
00375   //}
00376   //if (verbosity_level_ > 0) ROS_INFO("[BoxEstimation] Box dimensions x: %f, y: %f, z: %f ", pt0_bbox_features[0],  pt0_bbox_features[1],  pt0_bbox_features[2]);
00377   //if (verbosity_level_ > 0) ROS_INFO("[BoxEstimation] Eigen vectors: \n\t%f %f %f \n\t%f %f %f \n\t%f %f %f", pt0_bbox_features[3], pt0_bbox_features[4],
00378   //         pt0_bbox_features[5], pt0_bbox_features[6], pt0_bbox_features[7], pt0_bbox_features[8],
00379   //         pt0_bbox_features[9], pt0_bbox_features[10],pt0_bbox_features[11]);
00380 
00381   // TODO: we should get feedback on success from the compute function
00382   //return true;
00383 }
00384 
00386 
00389 void BoxEstimation::triangulate_box(boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZINormal> > cloud, std::vector<double> &coeff)
00390 {
00391   //pcl::PointXYZINormal current_point;
00392   geometry_msgs::Point32 current_point;
00393   triangle_mesh_msgs::Triangle triangle;
00394   mesh_ = boost::shared_ptr <BoxEstimation::OutputType> (new BoxEstimation::OutputType);
00395   //mesh_->points.resize(8);
00396   //mesh_->triangles.resize(12);
00397   //mesh_->header = cloud->header;
00398 
00399   int counter = 0;
00400   // create box vertices
00401   for (int i = -1; i <= 1; i = i+2)
00402   {
00403     for (int j = -1; j <= 1; j = j+2)
00404     {
00405       for (int k = -1; k <= 1; k = k+2)
00406       {
00407         // Movement along axes
00408         double moving[3];
00409         moving[0] = i * coeff[3]/2;
00410         moving[1] = j * coeff[4]/2;
00411         moving[2] = k * coeff[5]/2;
00412 
00413         // Move box center
00414         current_point.x = coeff[0] + moving[0]*coeff[6+0] + moving[1]*coeff[9+0] + moving[2]*coeff[12+0];
00415         current_point.y = coeff[1] + moving[0]*coeff[6+1] + moving[1]*coeff[9+1] + moving[2]*coeff[12+1];
00416         current_point.z = coeff[2] + moving[0]*coeff[6+2] + moving[1]*coeff[9+2] + moving[2]*coeff[12+2];
00417 
00418         //current_point.x = coeff[0] + i * coeff[3]/2;
00419         //current_point.y = coeff[1] + j * coeff[4]/2;
00420         //current_point.z = coeff[2] + k * coeff[5]/2;
00421 
00422         //mesh_->points[counter++].x = current_point.x;
00423         //mesh_->points[counter++].y = current_point.y;
00424         //mesh_->points[counter++].z = current_point.z;
00425 
00426         mesh_->points.push_back(current_point);
00427       }
00428     }
00429   }
00430 
00431   // fill in the box sides (2 triangles per side)
00432   triangle.i = 0, triangle.j = 1, triangle.k = 2;
00433   mesh_->triangles.push_back(triangle);
00434   triangle.i = 0, triangle.j = 1, triangle.k = 4;
00435   mesh_->triangles.push_back(triangle);
00436   triangle.i = 0, triangle.j = 2, triangle.k = 6;
00437   mesh_->triangles.push_back(triangle);
00438   triangle.i = 0, triangle.j = 6, triangle.k = 4;
00439   mesh_->triangles.push_back(triangle);
00440   triangle.i = 1, triangle.j = 4, triangle.k = 5;
00441   mesh_->triangles.push_back(triangle);
00442   triangle.i = 5, triangle.j = 4, triangle.k = 6;
00443   mesh_->triangles.push_back(triangle);
00444   triangle.i = 5, triangle.j = 7, triangle.k = 6;
00445   mesh_->triangles.push_back(triangle);
00446   triangle.i = 7, triangle.j = 6, triangle.k = 2;
00447   mesh_->triangles.push_back(triangle);
00448   triangle.i = 7, triangle.j = 3, triangle.k = 2;
00449   mesh_->triangles.push_back(triangle);
00450   triangle.i = 1, triangle.j = 2, triangle.k = 3;
00451   mesh_->triangles.push_back(triangle);
00452   triangle.i = 1, triangle.j = 3, triangle.k = 7;
00453   mesh_->triangles.push_back(triangle);
00454   triangle.i = 1, triangle.j = 5, triangle.k = 7;
00455   mesh_->triangles.push_back(triangle);
00456 
00457 
00458   mesh_->header.frame_id = frame_id_;
00459   mesh_->header.stamp = ros::Time::now();
00460 }
00461 
00463 
00466 void BoxEstimation::publish_marker (boost::shared_ptr<const pcl::PointCloud <pcl::PointXYZINormal> > cloud, std::vector<double> &coeff)
00467 {
00468   computeMarker (cloud, coeff);
00469   marker_pub_.publish (marker_);
00470 }
00471 
00473 
00476 void BoxEstimation::computeMarker (boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZINormal> > cloud, std::vector<double> coeff)
00477 {
00478   btMatrix3x3 box_rot (coeff[6], coeff[7], coeff[8],
00479                        coeff[9], coeff[10], coeff[11],
00480                        coeff[12], coeff[13], coeff[14]);
00481   btMatrix3x3 box_rot_trans (box_rot.transpose());
00482   btQuaternion qt;
00483   box_rot_trans.getRotation(qt);
00484 
00485   //marker_.header.frame_id = "base_link";
00486   //marker_.header.stamp = ros::Time();
00487   //marker_.header = cloud->header;
00488 
00489   marker_.header.frame_id = frame_id_;
00490   marker_.header.stamp = ros::Time::now();
00491   marker_.ns = "BoxEstimation";
00492   marker_.id = 0;
00493   marker_.type = visualization_msgs::Marker::CUBE;
00494   marker_.action = visualization_msgs::Marker::ADD;
00495   marker_.pose.position.x = coeff[0];
00496   marker_.pose.position.y = coeff[1];
00497   marker_.pose.position.z = coeff[2];
00498   marker_.pose.orientation.x = qt.x();
00499   marker_.pose.orientation.y = qt.y();
00500   marker_.pose.orientation.z = qt.z();
00501   marker_.pose.orientation.w = qt.w();
00502   marker_.scale.x = coeff[3];
00503   marker_.scale.y = coeff[4];
00504   marker_.scale.z = coeff[5];
00505   marker_.color.a = 0.75;
00506   marker_.color.r = 0.0;
00507   marker_.color.g = 1.0;
00508   marker_.color.b = 0.0;
00509   std::cerr << "BOX MARKER COMPUTED, WITH FRAME " << marker_.header.frame_id << std::endl;
00510 }
00511 
00512 #ifndef NO_BOXFIT_NODE
00513 #ifdef CREATE_NODE
00514 int main (int argc, char* argv[])
00515 {
00516   return standalone_node <BoxEstimation> (argc, argv);
00517 }
00518 #endif
00519 #endif
00520 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pcl_cloud_algos
Author(s): Nico Blodow, Dejan Pangercic, Zoltan-Csaba Marton
autogenerated on Sun Oct 6 2013 12:05:19