$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 // Author(s): Marius Muja and Matei Ciocarlie 00036 00037 #include "tabletop_object_detector/model_fitter.h" 00038 00039 #include "distance_field/propagation_distance_field.h" 00040 #include "tabletop_object_detector/iterative_distance_fitter.h" 00041 00042 namespace tabletop_object_detector { 00043 00044 DistanceFieldFitter::DistanceFieldFitter() : distance_voxel_grid_(NULL) 00045 { 00046 truncate_value_ = 0.05; 00047 distance_field_resolution_ = 0.002; 00048 } 00049 00050 DistanceFieldFitter::~DistanceFieldFitter() 00051 { 00052 delete distance_voxel_grid_; 00053 } 00054 00055 void DistanceFieldFitter::initializeFromBtVectors(const std::vector<btVector3> &points) 00056 { 00057 delete distance_voxel_grid_; 00058 distance_voxel_grid_ = NULL; 00059 00060 if (points.size() == 0) { 00061 return; 00062 } 00063 00064 btVector3 min = points[0], max = points[0]; 00065 for (size_t i=0; i<points.size(); ++i) 00066 { 00067 for (size_t j=0; j<3; ++j) 00068 { 00069 if (min[j] > points[i][j]) 00070 { 00071 min[j] = points[i][j]; 00072 } 00073 if (max[j] < points[i][j]) 00074 { 00075 max[j] = points[i][j]; 00076 } 00077 } 00078 } 00079 00080 ROS_DEBUG("Size: (%g,%g,%g, %g, %g, %g)",min[0], min[1], min[2], max[0], max[1], max[2]); 00081 00082 //the distance field is initialized as follows: match the size of the object, but add 00083 //padding equal to the truncate_value_ on each side. Resolution is constant regardless 00084 //of the size of the object. 00085 00086 //the only difference in along negative Z where we add only a very small padding, making 00087 //the assumptions that we are pretty sure where the table is (Z=0 by convention), all objects 00088 //have the origin on the bottom, and nothing is below the table 00089 //allow just two cells under the table, to deal with noise and such 00090 double table_padding = 2.5 * distance_field_resolution_; 00091 distance_voxel_grid_ = new distance_field::PropagationDistanceField(max[0]-min[0] + 2*truncate_value_, 00092 max[1]-min[1] + 2*truncate_value_, 00093 max[2]-min[2] + truncate_value_ + table_padding, 00094 distance_field_resolution_, 00095 min[0] - truncate_value_, 00096 min[1] - truncate_value_, 00097 min[2] - table_padding, 00098 2 * truncate_value_ ); 00099 distance_voxel_grid_->reset(); 00100 distance_voxel_grid_->addPointsToField(points); 00101 } 00102 00103 double dist(const btVector3 &v0, const btVector3 &v1) 00104 { 00105 return sqrt( (v1.x()-v0.x())*(v1.x()-v0.x()) + 00106 (v1.y()-v0.y())*(v1.y()-v0.y()) + 00107 (v1.z()-v0.z())*(v1.z()-v0.z()) ); 00108 } 00109 00119 std::vector<btVector3> interpolateTriangle(btVector3 v0, 00120 btVector3 v1, 00121 btVector3 v2, double min_res) 00122 { 00123 std::vector<btVector3> vectors; 00124 00125 //find out the interpolation resolution for the first coordinate 00126 //based on the size of the 0-1 and 0-2 edges 00127 double d01 = dist(v0, v1); 00128 double d02 = dist(v0, v2); 00129 double res_0 = min_res / std::max(d01, d02); 00130 00131 //perform the first interpolation 00132 //we do not want the vertices themselves, so we don't start at 0 00133 double t0=res_0; 00134 bool done = false; 00135 while (!done) 00136 { 00137 if (t0 >= 1.0) 00138 { 00139 t0 = 1.0; 00140 done = true; 00141 } 00142 //compute the resolution for the second interpolation 00143 btVector3 p1 = t0*v0 + (1-t0) * v1; 00144 btVector3 p2 = t0*v0 + (1-t0) * v2; 00145 double d12 = dist(p1, p2); 00146 double res_12 = min_res / d12; 00147 00148 //perform the second interpolation 00149 double t12 = 0; 00150 bool done12 = false; 00151 while (!done12) 00152 { 00153 if (t12 >= 1.0) 00154 { 00155 t12 = 1.0; 00156 done12 = true; 00157 } 00158 //actual point insertion 00159 //do not insert the vertices themselves 00160 if (t0!=1.0 || (t12!=0.0 && t12!=1.0)) 00161 { 00162 vectors.push_back( t12*p1 + (1.0 - t12)*p2 ); 00163 } 00164 t12 += res_12; 00165 } 00166 00167 t0 += res_0; 00168 } 00169 return vectors; 00170 } 00171 00172 void ModelToCloudFitter::sampleMesh(const arm_navigation_msgs::Shape &mesh, 00173 std::vector<btVector3> &btVectors, 00174 double resolution) 00175 { 00176 btVectors.reserve(mesh.vertices.size()); 00177 //vertices themselves get inserted explicitly here. If we inserted them 00178 //as part of triangles, we would insert each vertex multiple times 00179 typedef std::vector<geometry_msgs::Point>::const_iterator I; 00180 for (I i=mesh.vertices.begin(); i!=mesh.vertices.end(); i++) 00181 { 00182 btVectors.push_back(btVector3(i->x,i->y,i->z)); 00183 } 00184 00185 //sample triangle surfaces at a specified min-resolution 00186 //and insert the resulting points 00187 for (size_t i=0; i<mesh.triangles.size(); i+=3) 00188 { 00189 btVector3 v0( mesh.vertices.at( mesh.triangles.at(i+0) ).x, 00190 mesh.vertices.at( mesh.triangles.at(i+0) ).y, 00191 mesh.vertices.at( mesh.triangles.at(i+0) ).z); 00192 btVector3 v1( mesh.vertices.at( mesh.triangles.at(i+1) ).x, 00193 mesh.vertices.at( mesh.triangles.at(i+1) ).y, 00194 mesh.vertices.at( mesh.triangles.at(i+1) ).z); 00195 btVector3 v2( mesh.vertices.at( mesh.triangles.at(i+2) ).x, 00196 mesh.vertices.at( mesh.triangles.at(i+2) ).y, 00197 mesh.vertices.at( mesh.triangles.at(i+2) ).z); 00198 std::vector<btVector3> triangleVectors = interpolateTriangle(v0, v1, v2, resolution); 00199 btVectors.insert(btVectors.begin(), triangleVectors.begin(), triangleVectors.end()); 00200 } 00201 } 00202 00203 00204 void DistanceFieldFitter::initializeFromMesh(const arm_navigation_msgs::Shape &mesh) 00205 { 00206 std::vector<btVector3> btVectors; 00207 //we use a slightly larger resolution than the distance field, in an attempt to bring 00208 //down pre-computation time 00209 sampleMesh(mesh, btVectors, 1.5 * distance_field_resolution_ ); 00210 initializeFromBtVectors(btVectors); 00211 } 00212 00213 00214 } //namespace