Go to the documentation of this file.00001 #ifndef _wam_pomdp3piles_h_
00002 #define _wam_pomdp3piles_h_
00003
00004 #include "ros/this_node.h"
00005 #include "ros/names.h"
00006 #include "ros/node_handle.h"
00007 #include "ros/rate.h"
00008 #include <list>
00009
00010 #include "mutex.h"
00011 #include "GenericPolicy.h"
00012
00013
00014
00015
00016 #include "std_srvs/Empty.h"
00017 #include "std_msgs/Int32.h"
00018 #include "estirabot_msgs/belief_summary.h"
00019 #include "estirabot_msgs/belief.h"
00020 #include "estirabot_msgs/obs2action.h"
00021
00022
00023
00024 #define LOGFILE "log.txt"
00025
00026 #define MAXNUMB 5 //maxnumb + 1
00027 #define AZONEMSG 1
00028 #define BZONEMSG 2
00029 #define ANYZONE 0
00030
00031 enum {
00032
00033 TAKEHIGH,
00034 TAKELOW,
00035 CHANGEPILE,
00036 FOLDLOW,
00037 SPREAD,
00038 FLIP,
00039 SHAKE,
00040 FOLDHIGH,
00041 MOVEAWAY,
00042 DUMMY
00043 };
00044
00045 enum {
00046 STRAIGHT,
00047 ISOMETRIC,
00048 PEG
00049 };
00050
00051 class Pomdp
00052 {
00053 private:
00054 CMutex execution_mutex;
00055 bool execution_flag;
00056 int actioncount;
00057 int last_action_;
00058 std::string pomdpfile_;
00059 std::vector<int> probablestates;
00060
00061 ros::NodeHandle node_handle_;
00062
00063 Policy2piles *myPolicy;
00064
00065
00066 ros::Publisher focused_obj_label_publisher;
00067 std_msgs::Int32 ObjLabel_msg;
00068 ros::Publisher belief_summary_publisher;
00069 estirabot_msgs::belief_summary belief_summary_msg;
00070 ros::Publisher belief_publisher;
00071 estirabot_msgs::belief belief_msg;
00072
00073
00074
00075
00076 ros::ServiceServer execution_flow_control_server_;
00077 bool execution_flow_controlCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00078 ros::ServiceServer obs2action_server_;
00079 bool obs2actionCallback(estirabot_msgs::obs2action::Request &req, estirabot_msgs::obs2action::Response &res);
00080 ros::ServiceServer resetPOMDP_server_;
00081 bool resetPOMDPCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00082
00083
00084
00085
00086
00087
00088
00089 void publish_belief();
00090 public:
00108 Pomdp();
00109
00122 void mainLoop(void);
00123
00124 };
00125 #endif
00126