shot.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Ryohei Ueda, JSK Lab
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 JSK Lab. 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  */
00036 
00037 #include <pluginlib/class_list_macros.h>
00038 #include "pcl_ros/features/shot.h"
00039 
00040 void 
00041 pcl_ros::SHOTEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
00042 {
00043   PointCloudOut output;
00044   output.header = cloud->header;
00045   pub_output_.publish (output.makeShared ());
00046 }
00047 
00048 void 
00049 pcl_ros::SHOTEstimation::computePublish (const PointCloudInConstPtr &cloud,
00050                                          const PointCloudNConstPtr &normals,
00051                                          const PointCloudInConstPtr &surface,
00052                                          const IndicesPtr &indices)
00053 {
00054   // Set the parameters
00055   impl_.setKSearch (k_);
00056   impl_.setRadiusSearch (search_radius_);
00057 
00058   // Set the inputs
00059   impl_.setInputCloud (cloud);
00060   impl_.setIndices (indices);
00061   impl_.setSearchSurface (surface);
00062   impl_.setInputNormals (normals);
00063   // Estimate the feature
00064   PointCloudOut output;
00065   impl_.compute (output);
00066 
00067   // Publish a Boost shared ptr const data
00068   // Enforce that the TF frame and the timestamp are copied
00069   output.header = cloud->header;
00070   pub_output_.publish (output.makeShared ());
00071 }
00072 
00073 typedef pcl_ros::SHOTEstimation SHOTEstimation;
00074 PLUGINLIB_DECLARE_CLASS (pcl, SHOTEstimation, SHOTEstimation, nodelet::Nodelet);
00075 


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Aug 26 2015 15:25:31