decpomdp_loader.h
Go to the documentation of this file.
00001 
00025 #ifndef _DECPOMDP_LOADER_H_
00026 #define _DECPOMDP_LOADER_H_
00027 
00028 #include <string>
00029 
00030 #include <ros/ros.h>
00031 
00032 
00033 
00034 #ifdef HAVE_MADP
00035 
00036 #include <madp/PlanningUnitDecPOMDPDiscrete.h>
00037 #include <madp/FactoredDecPOMDPDiscrete.h>
00038 #include <madp/DecPOMDPDiscrete.h>
00039 
00040 #endif
00041 
00042 
00043 
00044 namespace mdm_library
00045 {
00046 class DecPOMDPLoader
00047 {
00048 protected:
00049     ros::NodeHandle nh_;
00050 
00051 public:
00052     DecPOMDPLoader ( const std::string& problem_file );
00053 
00054 #ifdef HAVE_MADP
00055 
00056     boost::shared_ptr<DecPOMDPDiscreteInterface> decpomdp_;
00057 
00058     const boost::shared_ptr<DecPOMDPDiscreteInterface> GetDecPOMDP();
00059     PlanningUnitMADPDiscreteParameters GetParams();
00060 
00061     void publishActionMetadata ();
00062     void publishStateMetadata ( boost::shared_ptr<FactoredDecPOMDPDiscrete> f );
00063     void publishStateMetadata ( boost::shared_ptr<DecPOMDPDiscrete> d );
00064     void publishObservationMetadata ();
00065     void publishInitialStateDistribution ( boost::shared_ptr<FactoredDecPOMDPDiscrete> f );
00066     void publishInitialStateDistribution ( boost::shared_ptr<DecPOMDPDiscrete> d );
00067 private:
00068     ros::Publisher action_metadata_pub_;
00069     ros::Publisher state_metadata_pub_;
00070     ros::Publisher observation_metadata_pub_;
00071     ros::Publisher initial_state_distribution_pub_;
00072 
00073 #endif
00074 };
00075 }
00076 
00077 #endif


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