$search
00001 /* 00002 * blob.cc 00003 * Mac Mason <mmason@willowgarage.com> 00004 * 00005 * Implementation. See include/semanticmodel/blob.hh. 00006 */ 00007 00008 #include <limits> 00009 #include <vector> 00010 #include <boost/foreach.hpp> 00011 #define foreach BOOST_FOREACH 00012 #include "ros/ros.h" // For debugging. 00013 #include "pcl16/surface/convex_hull.h" 00014 #include "semanticmodel/blob.hh" 00015 00016 namespace semanticmodel 00017 { 00018 Blob::Blob(const PointCloud::ConstPtr& cluster) 00019 : cloud(new PointCloud(*cluster)), hull(new PointCloud()), id(next_id++) 00020 { 00021 /* 00022 * TODO TODO TODO: 00023 * We really should be giving each blob its own coordinate frame, and 00024 * using tf to keep track of where they are. 00025 */ 00026 hull->header.frame_id = cloud->header.frame_id; 00027 hullerize(cluster); 00028 } 00029 00030 bool Blob::overlaps(const Blob& rhs) const 00031 { 00032 return oneSidedIntersect(hull, rhs.hull) || 00033 oneSidedIntersect(rhs.hull, hull); 00034 } 00035 00036 void Blob::mergeFrom(const Blob& rhs) 00037 { 00038 // For the moment, give merged blobs the lesser of their unique ids. 00039 id = std::min(id, rhs.id); 00040 (*cloud) += *(rhs.cloud); 00041 (*hull) += *(rhs.hull); 00042 hullerize(hull); 00043 } 00044 00045 void Blob::RGB(float& r, float& g, float& b) const 00046 { 00047 r = g = b = 0.0; 00048 foreach(Point& p, *cloud) 00049 { 00050 // PCL, you are so very odd. 00051 uint32_t rgb = *reinterpret_cast<int*>(&p.rgb); 00052 uint8_t rb = (rgb >> 16) & 0x0000ff; 00053 uint8_t gb = (rgb >> 8) & 0x0000ff; 00054 uint8_t bb = (rgb) & 0x0000ff; 00055 00056 r += rb / 255.0; 00057 g += gb / 255.0; 00058 b += bb / 255.0; 00059 } 00060 00061 r /= cloud->points.size(); 00062 g /= cloud->points.size(); 00063 b /= cloud->points.size(); 00064 } 00065 00066 void Blob::size(double& x, double& y, double& z) const 00067 { 00068 float minx = cloud->points[0].x; 00069 float maxx = cloud->points[0].x; 00070 float miny = cloud->points[0].y; 00071 float maxy = cloud->points[0].y; 00072 float minz = cloud->points[0].z; 00073 float maxz = cloud->points[0].z; 00074 foreach(const Point& p, *cloud) 00075 { 00076 minx = std::min(minx, p.x); 00077 maxx = std::max(maxx, p.x); 00078 miny = std::min(miny, p.y); 00079 maxy = std::max(maxy, p.y); 00080 minz = std::min(minz, p.z); 00081 maxz = std::max(maxz, p.z); 00082 } 00083 x = maxx - minx; 00084 y = maxy - miny; 00085 z = maxz - minz; 00086 } 00087 00088 // Note abuse of Blob::PointCloud typedef to mean pcl16::PointCloud<...>. This 00089 // way, we can keep our typedefs private. 00090 Blob::PointCloud::Ptr Blob::flatten(PointCloud::Ptr& in, double z) 00091 { 00092 PointCloud::Ptr res(new PointCloud(*in)); 00093 foreach(Point& p, *res) 00094 p.z = z; 00095 return res; 00096 } 00097 00098 void Blob::MergeBlobWithSet(std::vector<Blob*>& objects, Blob* blob) 00099 { 00100 // Hooray for helper functions. 00101 objects.push_back(blob); 00102 while (MergeBlobWithSetHelper(objects)) {}; 00103 } 00104 00105 bool Blob::MergeBlobWithSetHelper(std::vector<Blob*>& objects) 00106 { 00107 Blob* end = objects.back(); 00108 for (size_t i = 0 ; i < objects.size() - 1 ; ++i) 00109 { 00110 if (objects[i]->overlaps(*end)) 00111 { 00112 ROS_DEBUG_STREAM_NAMED ("merge_blobs", "Merging blob " << end->id << 00113 " into " << objects[i]->id); 00114 objects[i]->mergeFrom(*end); 00115 delete end; 00116 objects.pop_back(); 00117 std::swap(objects[i], objects.back()); 00118 return true; 00119 } 00120 } 00121 return false; 00122 } 00123 00124 // See above comment about typedef abuse. 00125 void Blob::hullerize(const Blob::PointCloud::ConstPtr& cloud) 00126 { 00127 (*hull) += (*cloud); // Not necessarily flat, or a hull, after this. 00128 PointCloud::Ptr flat(Blob::flatten(hull, 0.0)); 00129 pcl16::ConvexHull<Point> huller; 00130 huller.setInputCloud(flat); 00131 huller.setDimension(2); // Ok since we flattened it 00132 huller.reconstruct(*hull); // Now it's flat and a hull. 00133 } 00134 00135 // Yet more typedef abuse. 00136 bool Blob::oneSidedIntersect(const Blob::PointCloud::ConstPtr& p1, 00137 const Blob::PointCloud::ConstPtr& p2) const 00138 { 00139 size_t n = p1->points.size(); 00140 for (size_t i = 0 ; i < n ; ++i) 00141 { 00142 size_t j; 00143 if (i > 0) 00144 j = i - 1; 00145 else 00146 j = n - 1; 00147 00148 double min1, max1, min2, max2; 00149 projectOntoNormal(p1, p1->points[i], p1->points[j], min1, max1); 00150 projectOntoNormal(p2, p1->points[i], p1->points[j], min2, max2); 00151 if (max2 < min1 || max1 < min2) 00152 return false; 00153 } 00154 return true; 00155 } 00156 00157 // Yet yet more typedef abuse. 00158 void Blob::projectOntoNormal(const Blob::PointCloud::ConstPtr& poly, 00159 const Point& q1, const Point& q2, 00160 double& inf, double& sup) const 00161 { 00162 Eigen::Vector2f d; 00163 d[0] = q2.x - q1.x; 00164 d[1] = q2.y - q1.y; 00165 Eigen::Vector2f perp(d[1], -d[0]); 00166 perp.normalize(); 00167 inf = std::numeric_limits<double>::infinity(); 00168 sup = std::numeric_limits<double>::infinity(); 00169 foreach(const Point& p, *poly) 00170 { 00171 Eigen::Vector2f v(p.x, p.y); 00172 float proj = perp.dot(v); 00173 if (!pcl_isfinite(inf) || proj < inf) 00174 inf = proj; 00175 if (!pcl_isfinite(sup) || proj > sup) 00176 sup = proj; 00177 } 00178 assert (pcl_isfinite(inf)); 00179 assert (pcl_isfinite(sup)); 00180 } 00181 00182 unsigned int Blob::next_id = 0; 00183 00184 }