trackerinterface.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2012, PAL Robotics, S.L.
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 PAL Robotics, S.L. 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  * @file trackerinterface.h
00035  * @author Bence Magyar
00036  * @date March 2012
00037  * @version 0.1
00038  * @brief This class describes an interface derived from the blort tracker as a complete application.
00039  * It defines the system logic of recovery and track modes and confidence states.
00040  * @namespace pal_blort
00041  */
00042 
00043 #ifndef BLORTTRACKER_H
00044 #define BLORTTRACKER_H
00045 
00046 #include <opencv2/core/core.hpp>
00047 #include <boost/foreach.hpp>
00048 
00049 namespace blort_ros
00050 {
00051     enum tracker_mode
00052     {
00053         TRACKER_RECOVERY_MODE,
00054         TRACKER_TRACKING_MODE,
00055         TRACKER_LOCKED_MODE
00056     };
00057 
00058     enum tracker_confidence
00059     {
00060         TRACKER_CONF_GOOD,
00061         TRACKER_CONF_FAIR,
00062         TRACKER_CONF_LOST
00063     };
00064 
00065     class TrackerInterface
00066     {
00067     protected:
00068         std::map<std::string, tracker_mode> current_modes;
00069         std::map<std::string, tracker_confidence> current_confs;
00070         cv::Mat last_image;
00071 
00072     public:
00073         TrackerInterface()
00074         {
00075         }
00076         virtual void track() = 0;
00077         virtual void recovery() = 0;
00078         void process(cv::Mat img)
00079         {
00080             last_image = img;
00081             tracker_mode current_mode = TRACKER_RECOVERY_MODE;
00082             typedef std::pair<std::string, blort_ros::tracker_mode> NameModePair_t;
00083             BOOST_FOREACH(NameModePair_t item, current_modes)
00084             {
00085                 if(item.second != current_mode)
00086                 {
00087                     //FIXME tracking and locked mode are equivalent for now
00088                     current_mode = item.second;
00089                     break;
00090                 }
00091             }
00092             switch(current_mode)
00093             {
00094             case TRACKER_RECOVERY_MODE:
00095                 recovery();
00096                 break;
00097             case TRACKER_TRACKING_MODE:
00098                 track();
00099                 break;
00100             case TRACKER_LOCKED_MODE:
00101                 track(); //FIXME a bit hacky
00102                 break;
00103             }
00104         }
00105 
00106         virtual void switchToTracking(std::string id)
00107         {
00108           current_confs[id] = TRACKER_CONF_FAIR;
00109           current_modes[id] = TRACKER_TRACKING_MODE;
00110         }
00111 
00112         virtual void switchToRecovery(std::string id)
00113         {
00114           current_confs[id] = TRACKER_CONF_LOST;
00115           current_modes[id] = TRACKER_RECOVERY_MODE;
00116         }
00117 
00118         virtual void reset(std::string id){ switchToRecovery(id); }
00119         tracker_mode getMode(std::string id){ return current_modes[id]; }
00120         tracker_confidence getConfidence(std::string id){ return current_confs[id]; }
00121     };
00122 }
00123 
00124 #endif // BLORTTRACKER_H


blort_ros
Author(s): Bence Magyar
autogenerated on Wed Aug 26 2015 15:24:39