abstract-search.hh
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2006-2012, Mirko Maischberger <mirko.maischberger@gmail.com>
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  *
00018  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  *  POSSIBILITY OF SUCH DAMAGE.
00030  *
00031  */
00032 
00033 #include <iostream>
00034 
00035 #ifndef METS_ABSTRACT_SEARCH_HH_
00036 #define METS_ABSTRACT_SEARCH_HH_
00037 
00038 namespace mets {
00039 
00042 
00051   class solution_recorder {
00052   public:
00054     solution_recorder() {}
00056     solution_recorder(const solution_recorder&);
00058     solution_recorder& operator=(const solution_recorder&);
00059 
00061     virtual 
00062     ~solution_recorder();
00063 
00069     virtual bool 
00070     accept(const feasible_solution& sol) = 0;
00071 
00072     virtual gol_type 
00073     best_cost() const = 0;
00074   };
00075 
00079   template<typename move_manager_type>
00080   class abstract_search : public subject< abstract_search<move_manager_type> >
00081   {
00082   public:
00095     abstract_search(feasible_solution& working,
00096                     solution_recorder& recorder,
00097                     move_manager_type& moveman)
00098       : subject<abstract_search<move_manager_type> >(), 
00099         solution_recorder_m(recorder),
00100         working_solution_m(working),
00101         moves_m(moveman),
00102         current_move_m(),
00103         step_m()
00104     { }
00105                          
00107     abstract_search(const abstract_search<move_manager_type>&);
00109     abstract_search& operator==(const abstract_search<move_manager_type>&);
00110 
00112     virtual 
00113     ~abstract_search() 
00114     { };
00115 
00116     enum {
00118       MOVE_MADE = 0,  
00120       IMPROVEMENT_MADE,
00122       ITERATION_BEGIN,
00124       ITERATION_END,
00126       LAST
00127     };
00128      
00135     virtual void
00136     search() 
00137       throw(no_moves_error) = 0;
00138 
00140     const solution_recorder&
00141     recorder() const 
00142     { return solution_recorder_m; };
00143     
00145     const feasible_solution&
00146     working() const 
00147     { return working_solution_m; }
00148     
00149     feasible_solution&
00150     working() 
00151     { return working_solution_m; }
00152 
00154     const move&
00155     current_move() const 
00156     { return **current_move_m; }
00157 
00159     move&
00160     current_move() 
00161     { return **current_move_m; }
00162  
00164     const move_manager_type& 
00165     move_manager() const 
00166     { return moves_m; }
00167 
00169     move_manager_type& 
00170     move_manager() 
00171     { return moves_m; }
00172 
00179     int
00180     step() const 
00181     { return step_m; }
00182     
00183   protected:
00184     solution_recorder& solution_recorder_m;
00185     feasible_solution& working_solution_m;
00186     move_manager_type& moves_m;
00187     typename move_manager_type::iterator current_move_m;
00188     int step_m;
00189   };
00190 
00192 
00195 
00200   class best_ever_solution : public solution_recorder 
00201   {
00202   public:
00209     best_ever_solution(evaluable_solution& best) : 
00210       solution_recorder(), 
00211       best_ever_m(best) 
00212     { }
00213 
00215     best_ever_solution();
00217     best_ever_solution(const best_ever_solution&);
00219     best_ever_solution& operator=(const best_ever_solution&);
00220 
00224     bool accept(const feasible_solution& sol);
00225 
00227     const evaluable_solution& best_seen() const 
00228     { return best_ever_m; }
00229 
00231     gol_type best_cost() const 
00232     { return best_ever_m.cost_function(); }
00233   protected:
00235     evaluable_solution& best_ever_m;
00236   };
00237     
00239   template<typename move_manager_type>
00240   class search_listener : public observer<abstract_search<move_manager_type> >
00241   {
00242   public:
00243     typedef abstract_search<move_manager_type> search_type;
00247     explicit
00248     search_listener() : observer<search_type>() 
00249     { }
00250 
00252     search_listener(const search_listener<search_type>& other);
00253     search_listener<search_type>& 
00254     operator=(const search_listener<search_type>& other);
00255 
00257     virtual 
00258     ~search_listener() 
00259     { }
00260 
00263     virtual void
00264     update(search_type* algorithm) = 0;
00265   };
00266 
00267 
00268   template<typename neighborhood_t>
00269   struct iteration_logger : public mets::search_listener<neighborhood_t>
00270   {
00271     explicit
00272     iteration_logger(std::ostream& o) 
00273       : mets::search_listener<neighborhood_t>(), 
00274         iteration(0), 
00275         os(o) 
00276     { }
00277     
00278     void 
00279     update(mets::abstract_search<neighborhood_t>* as) 
00280     {
00281       const mets::feasible_solution& p = as->working();
00282       if(as->step() == mets::abstract_search<neighborhood_t>::MOVE_MADE)
00283         {
00284           os << iteration++ << "\t" 
00285              << static_cast<const mets::evaluable_solution&>(p).cost_function()
00286              << "\n";
00287         }
00288     }
00289     
00290   protected:
00291     int iteration;
00292     std::ostream& os;
00293   };
00294 
00295   template<typename neighborhood_t>
00296   struct improvement_logger : public mets::search_listener<neighborhood_t>
00297   {
00298     explicit
00299     improvement_logger(std::ostream& o, gol_type epsilon = 1e-7) 
00300       : mets::search_listener<neighborhood_t>(), 
00301         iteration_m(0), 
00302         best_m(std::numeric_limits<double>::max()),
00303         os_m(o),
00304         epsilon_m(epsilon)
00305     { }
00306     
00307     void 
00308     update(mets::abstract_search<neighborhood_t>* as) 
00309     {
00310       const mets::feasible_solution& p = as->working();
00311 
00312       if(as->step() == mets::abstract_search<neighborhood_t>::MOVE_MADE)
00313         {
00314           iteration_m++;
00315           double val = static_cast<const mets::evaluable_solution&>(p)
00316             .cost_function();
00317           if(val < best_m - epsilon_m) 
00318             {        
00319               best_m = val;
00320               os_m << iteration_m << "\t" 
00321                    << best_m
00322                    << " (*)\n";
00323             }
00324         }
00325     }
00326     
00327   protected:
00328     int iteration_m;
00329     double best_m;
00330     std::ostream& os_m;
00331     gol_type epsilon_m;
00332   };
00333 
00335 
00336 
00337 }
00338 
00339 inline mets::solution_recorder::~solution_recorder() 
00340 { }
00341 
00342 inline bool
00343 mets::best_ever_solution::accept(const mets::feasible_solution& sol)
00344 {
00345   const evaluable_solution& s = dynamic_cast<const mets::evaluable_solution&>(sol);
00346   if(s.cost_function() < best_ever_m.cost_function())
00347     {
00348       best_ever_m.copy_from(s);
00349       return true;
00350     }
00351   return false;
00352 }
00353 
00354 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:31