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/orientation_tangent.h> 00036 00037 using namespace std; 00038 00039 // -------------------------------------------------------------- 00040 /* See function definition */ 00041 // -------------------------------------------------------------- 00042 OrientationTangent::OrientationTangent(const double ref_x, 00043 const double ref_y, 00044 const double ref_z, 00045 SpectralAnalysis& spectral_information) 00046 { 00047 reference_direction_[0] = ref_x; 00048 reference_direction_[1] = ref_y; 00049 reference_direction_[2] = ref_z; 00050 reference_direction_flipped_[0] = -reference_direction_[0]; 00051 reference_direction_flipped_[1] = -reference_direction_[1]; 00052 reference_direction_flipped_[2] = -reference_direction_[2]; 00053 00054 spectral_information_ = &spectral_information; 00055 } 00056 00057 // -------------------------------------------------------------- 00058 /* See function definition */ 00059 // -------------------------------------------------------------- 00060 string OrientationTangent::getName() const 00061 { 00062 return string("TODO: Add a name to this feature."); 00063 } 00064 00065 // -------------------------------------------------------------- 00066 /* See function definition */ 00067 // -------------------------------------------------------------- 00068 void OrientationTangent::clearShared() 00069 { 00070 spectral_information_->clearSpectral(); 00071 } 00072 00073 // -------------------------------------------------------------- 00074 /* See function definition */ 00075 // -------------------------------------------------------------- 00076 int OrientationTangent::precompute(const sensor_msgs::PointCloud& data, 00077 cloud_kdtree::KdTree& data_kdtree, 00078 const std::vector<const geometry_msgs::Point32*>& interest_pts) 00079 { 00080 // Compute spectral information if not already done 00081 if (spectral_information_->isSpectralComputed() == false) 00082 { 00083 if (spectral_information_->analyzeInterestPoints(data, data_kdtree, interest_pts) < 0) 00084 { 00085 return -1; 00086 } 00087 } 00088 00089 // Retrieve necessary spectral information this class needs to compute features 00090 local_directions_ = &(spectral_information_->getTangents()); 00091 00092 // verify the normals are for the interest points 00093 if (local_directions_->size() != interest_pts.size()) 00094 { 00095 ROS_ERROR("OrientationTangent::precompute() inconsistent number of points and spectral info"); 00096 local_directions_ = NULL; 00097 return -1; 00098 } 00099 00100 return 0; 00101 } 00102 00103 // -------------------------------------------------------------- 00104 /* See function definition */ 00105 // -------------------------------------------------------------- 00106 int OrientationTangent::precompute(const sensor_msgs::PointCloud& data, 00107 cloud_kdtree::KdTree& data_kdtree, 00108 const std::vector<const std::vector<int>*>& interest_region_indices) 00109 { 00110 // Compute spectral information if not already done 00111 if (spectral_information_->isSpectralComputed() == false) 00112 { 00113 if (spectral_information_->analyzeInterestRegions(data, data_kdtree, interest_region_indices) < 0) 00114 { 00115 return -1; 00116 } 00117 } 00118 00119 // Retrieve necessary spectral information this class needs to compute features 00120 local_directions_ = &(spectral_information_->getTangents()); 00121 00122 // verify the normals are for the interest regions 00123 if (local_directions_->size() != interest_region_indices.size()) 00124 { 00125 ROS_ERROR("OrientationTangent::precompute() inconsistent number of regions and spectral info"); 00126 local_directions_ = NULL; 00127 return -1; 00128 } 00129 00130 return 0; 00131 } 00132