controller_mdp.h
Go to the documentation of this file.
00001 
00025 #ifndef _CONTROLLER_MDP_H_
00026 #define _CONTROLLER_MDP_H_
00027 
00028 #include <string>
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <mdm_library/common_defs.h>
00033 #include <mdm_library/control_layer_base.h>
00034 #include <mdm_library/decpomdp_loader.h>
00035 #include <mdm_library/mdp_policy.h>
00036 #include <mdm_library/reward_model.h>
00037 #include <mdm_library/WorldSymbol.h>
00038 
00039 
00040 
00041 namespace mdm_library
00042 {
00048 class ControllerMDP: public ControlLayerBase
00049 {
00050 public:
00051 #ifdef HAVE_MADP
00052 
00061     ControllerMDP ( const std::string& policy_file_path,
00062                     const std::string& problem_file_path,
00063                     const CONTROLLER_STATUS initial_status = STARTED );
00064 #endif
00065 
00066     ControllerMDP ( const std::string& policy_file_path,
00067                     const CONTROLLER_STATUS initial_status = STARTED );
00068 
00069     void loadPolicyVector ( const std::string& policy_vector_path );
00070 
00071     void loadRewardMatrix ( const std::string& reward_matrix_path );
00072 
00078     void act ( const uint32_t state );
00079 
00084     virtual void stateCallback ( const WorldSymbolConstPtr& msg ) = 0;
00085 
00087     size_t getNumberOfActions ();
00089     size_t getNumberOfStates ();
00090 
00091 protected:
00093     void publishAction ( uint32_t a );
00095     void publishReward ( uint32_t s, uint32_t a );
00096 
00097     boost::shared_ptr<RewardModel> R_ptr_;
00098     boost::shared_ptr<MDPPolicy> policy_ptr_;
00100     boost::shared_ptr<DecPOMDPLoader> loader_;
00102     size_t number_of_states_;
00104     size_t number_of_actions_;
00105 
00107     ros::Subscriber state_sub_;
00109     ros::Publisher action_pub_;
00111     ros::Publisher reward_pub_;
00112 };
00113 }
00114 
00115 #endif


mdm_library
Author(s): Joao Messias
autogenerated on Wed Aug 26 2015 12:28:41