$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage 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 #include <ias_descriptors_3d/channel.h> 00036 00037 using namespace std; 00038 00039 // -------------------------------------------------------------- 00040 /* See function definition */ 00041 // -------------------------------------------------------------- 00042 Channel::Channel(const string& channel_name) 00043 { 00044 channel_name_ = channel_name; 00045 result_size_ = 1; 00046 result_size_defined_ = true; 00047 } 00048 00049 // -------------------------------------------------------------- 00050 /* See function definition */ 00051 // -------------------------------------------------------------- 00052 void Channel::clearShared() 00053 { 00054 } 00055 00056 // -------------------------------------------------------------- 00057 /* See function definition */ 00058 // -------------------------------------------------------------- 00059 std::string Channel::getName() const 00060 { 00061 return string("TODO: Add a name to this feature."); 00062 } 00063 00064 // -------------------------------------------------------------- 00065 /* See function definition */ 00066 // -------------------------------------------------------------- 00067 int Channel::precompute(const sensor_msgs::PointCloud& data, 00068 cloud_kdtree::KdTree& data_kdtree, 00069 const std::vector<const geometry_msgs::Point32*>& interest_pts) 00070 { 00071 return 0; 00072 } 00073 00074 // -------------------------------------------------------------- 00075 /* See function definition */ 00076 // -------------------------------------------------------------- 00077 int Channel::precompute(const sensor_msgs::PointCloud& data, 00078 cloud_kdtree::KdTree& data_kdtree, 00079 const std::vector<const std::vector<int>*>& interest_region_indices) 00080 { 00081 return 0; 00082 } 00083 00084 // -------------------------------------------------------------- 00085 /* See function definition */ 00086 // -------------------------------------------------------------- 00087 void Channel::doComputation(const sensor_msgs::PointCloud& data, 00088 cloud_kdtree::KdTree& data_kdtree, 00089 const std::vector<const geometry_msgs::Point32*>& interest_pts, 00090 std::vector<std::vector<float> >& results) 00091 { 00092 // ---------------------------------------------- 00093 // Lookup the channel index corresponding to the given name 00094 int channel_idx = cloud_geometry::getChannelIndex(data, channel_name_); 00095 if (channel_idx < 0) 00096 { 00097 ROS_ERROR("Channel::doComputation() could not find channel %s in given point cloud", channel_name_.c_str()); 00098 return; 00099 } 00100 const std::vector<sensor_msgs::ChannelFloat32>& pt_cloud_chans = data.channels; 00101 00102 // ---------------------------------------------- 00103 // For each interest point, look up its index in the point cloud and then copy the 00104 // specified channel value 00105 int nbr_interest_pts = interest_pts.size(); 00106 #pragma omp parallel for 00107 for (int i = 0 ; i < nbr_interest_pts ; i++) 00108 { 00109 // -------------------------- 00110 if (interest_pts[static_cast<size_t> (i)] == NULL) 00111 { 00112 ROS_WARN("Channel::doComputation() passed NULL interest point %u", i); 00113 continue; 00114 } 00115 const geometry_msgs::Point32& curr_interest_pt = *(interest_pts[static_cast<size_t> (i)]); 00116 00117 // -------------------------- 00118 // Look for the interest point in the point cloud 00119 vector<int> neighbor_indices; 00120 vector<float> neighbor_distances; // unused 00121 data_kdtree.nearestKSearch(curr_interest_pt, 1, neighbor_indices, neighbor_distances); 00122 unsigned int nearest_pt_idx = neighbor_indices.at(0); 00123 const geometry_msgs::Point32& nearest_pt = data.points[nearest_pt_idx]; 00124 00125 // -------------------------- 00126 // Verify the nearest point is the same as the given interest point 00127 if (cloud_geometry::distances::pointToPointDistanceSqr(curr_interest_pt, nearest_pt) > 1e-8) 00128 { 00129 ROS_WARN("Channel::doComputation() could not find point (%f,%f,%f) in the given point cloud", 00130 curr_interest_pt.x, curr_interest_pt.y, curr_interest_pt.z); 00131 continue; 00132 } 00133 00134 // -------------------------- 00135 // Copy the channel value 00136 results[static_cast<size_t> (i)].resize(result_size_); 00137 results[static_cast<size_t> (i)][0] = pt_cloud_chans[channel_idx].values[nearest_pt_idx]; 00138 } 00139 } 00140 00141 // -------------------------------------------------------------- 00142 /* See function definition */ 00143 // -------------------------------------------------------------- 00144 void Channel::doComputation(const sensor_msgs::PointCloud& data, 00145 cloud_kdtree::KdTree& data_kdtree, 00146 const std::vector<const vector<int>*>& interest_region_indices, 00147 std::vector<std::vector<float> >& results) 00148 { 00149 // ---------------------------------------------- 00150 // Lookup the channel index corresponding to the given name 00151 int channel_idx = cloud_geometry::getChannelIndex(data, channel_name_); 00152 if (channel_idx < 0) 00153 { 00154 ROS_ERROR("Channel::doComputation() could not find channel %s in given point cloud", channel_name_.c_str()); 00155 return; 00156 } 00157 const std::vector<sensor_msgs::ChannelFloat32>& pt_cloud_chans = data.channels; 00158 00159 // ---------------------------------------------- 00160 // For each interest region, look up each of its points index in the point cloud 00161 // and then copy the region's average specified channel value 00162 int nbr_interest_regions = interest_region_indices.size(); 00163 #pragma omp parallel for 00164 for (int i = 0 ; i < nbr_interest_regions ; i++) 00165 { 00166 // -------------------------- 00167 if (interest_region_indices[static_cast<size_t> (i)] == NULL) 00168 { 00169 ROS_WARN("Channel::doComputation passed NULL interest region %u", i); 00170 continue; 00171 } 00172 const vector<int>& curr_interest_region = *(interest_region_indices[static_cast<size_t> (i)]); 00173 00174 // -------------------------- 00175 // Initialize average to 0 00176 results[static_cast<size_t> (i)].resize(result_size_); 00177 results[static_cast<size_t> (i)][0] = 0.0; 00178 00179 // -------------------------- 00180 // Sum each interest points' channel value 00181 unsigned int nbr_pts_in_region = curr_interest_region.size(); 00182 for (unsigned int j = 0 ; j < nbr_pts_in_region ; j++) 00183 { 00184 unsigned int curr_interest_pt_idx = static_cast<unsigned int> (curr_interest_region[j]); 00185 results[static_cast<size_t> (i)][0] += pt_cloud_chans[channel_idx].values.at( 00186 curr_interest_pt_idx); 00187 } 00188 00189 // -------------------------- 00190 // Average 00191 results[static_cast<size_t> (i)][0] /= static_cast<float> (nbr_pts_in_region); 00192 } 00193 }