anjockey.h
Go to the documentation of this file.
00001 #ifndef FEATURENAV_BASE_ANJOCKEY_H
00002 #define FEATURENAV_BASE_ANJOCKEY_H
00003 
00004 #include <boost/smart_ptr.hpp>
00005 
00006 #include <ros/ros.h>
00007 #include <ros/console.h>
00008 
00009 #include <lama_interfaces/AddInterface.h>
00010 
00011 #include <featurenav_base/typedef.h>
00012 #include <featurenav_base/ajockey.h>
00013 #include <featurenav_base/njockey.h>
00014 
00015 namespace featurenav_base {
00016 
00017 class ANJockey
00018 {
00019   public:
00020 
00021     ANJockey(const std::string& name, const std::string& segment_interface_name);
00022 
00023     std::string getLearningJockeyName() const;
00024     std::string getNavigatingJockeyName() const;
00025 
00026     void setExtractFeaturesFunction(feature_extractor_function_ptr f);
00027     void setDescriptorMatcherFunction(descriptor_matcher_function_ptr f);
00028 
00029   private:
00030 
00031     bool initMapSegmentInterface();
00032     bool canDo(const action_type action);
00033     void startDo(const action_type action);
00034 
00035     // Internals.
00036     ros::NodeHandle nh_;
00037     ros::NodeHandle private_nh_;
00038     std::string segment_interface_name_;  
00039     std::string segment_getter_name_;  
00040     std::string segment_setter_name_;  
00041 
00042     boost::scoped_ptr<AJockey> ajockey_ptr_;
00043     boost::scoped_ptr<NJockey> njockey_ptr_;
00044 
00045     bool learning_;
00046     bool navigating_;
00047 };
00048 
00049 } // namespace featurenav_base
00050 
00051 #endif /* FEATURENAV_BASE_ANJOCKEY_H */


featurenav_base
Author(s): Gaƫl Ecorchard
autogenerated on Sat Jun 8 2019 19:52:22