dotmod.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved. 
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #ifndef PCL_RECOGNITION_DOTMOD
00039 #define PCL_RECOGNITION_DOTMOD
00040 
00041 #include <vector>
00042 #include <cstddef>
00043 #include <string.h>
00044 #include <pcl/pcl_macros.h>
00045 #include <pcl/recognition/dot_modality.h>
00046 #include <pcl/recognition/dense_quantized_multi_mod_template.h>
00047 #include <pcl/recognition/mask_map.h>
00048 #include <pcl/recognition/region_xy.h>
00049 
00050 namespace pcl
00051 {
00052 
00053   struct DOTMODDetection
00054   {
00055     size_t bin_x;
00056     size_t bin_y;
00057     size_t template_id;
00058     float score;
00059   };
00060 
00065   class PCL_EXPORTS DOTMOD
00066   {
00067     public:
00069       DOTMOD (size_t template_width,
00070               size_t template_height);
00071 
00073       virtual ~DOTMOD ();
00074 
00080       size_t 
00081       createAndAddTemplate (const std::vector<DOTModality*> & modalities,
00082                             const std::vector<MaskMap*> & masks,
00083                             size_t template_anker_x,
00084                             size_t template_anker_y,
00085                             const RegionXY & region);
00086 
00087       void
00088       detectTemplates (const std::vector<DOTModality*> & modalities,
00089                        float template_response_threshold,
00090                        std::vector<DOTMODDetection> & detections,
00091                        const size_t bin_size) const;
00092 
00093       inline const DenseQuantizedMultiModTemplate &
00094       getTemplate (size_t template_id) const
00095       { 
00096         return (templates_[template_id]);
00097       }
00098 
00099       inline size_t
00100       getNumOfTemplates ()
00101       {
00102         return (templates_.size ());
00103       }
00104 
00105       void
00106       saveTemplates (const char * file_name) const;
00107 
00108       void
00109       loadTemplates (const char * file_name);
00110 
00111       void 
00112       serialize (std::ostream & stream) const;
00113 
00114       void 
00115       deserialize (std::istream & stream);
00116 
00117 
00118     private:
00120       size_t template_width_;
00122       size_t template_height_;
00124       std::vector<DenseQuantizedMultiModTemplate> templates_;
00125   };
00126 
00127 }
00128 
00129 #endif 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:25