pomdp.h
Go to the documentation of this file.
00001 #ifndef _wam_pomdp_h_
00002 #define _wam_pomdp_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 "Policy.h"
00012 
00013 // [publisher subscriber headers]
00014 
00015 // [service client headers]
00016 #include "std_srvs/Empty.h"
00017 #include "std_msgs/Int32.h"
00018 #include "iri_wam_common_msgs/wamaction.h"
00019 #include "iri_wam_common_msgs/obs_request.h"
00020 #include "iri_wam_common_msgs/belief_summary.h"
00021 #include "iri_wam_common_msgs/belief.h"
00022 
00023 // [action server client headers]
00024 
00025 #define LOGFILE "log.txt"
00026 
00027 #define MAXNUMB 5 //maxnumb + 1
00028 #define AZONEMSG 1
00029 #define BZONEMSG 2
00030 #define ANYZONE 0
00031 
00032 enum {
00033     //remember to change the other .h enums (dummy_pomdp)!
00034     TAKEHIGH,
00035     TAKELOW,
00036     CHANGEPILE,
00037     FOLDLOW,
00038     SPREAD,
00039     FLIP,
00040     SHAKE,
00041     FOLDHIGH,
00042     MOVEAWAY,
00043     DUMMY
00044 };
00045 
00046 enum {
00047     STRAIGHT,
00048     ISOMETRIC,
00049     PEG
00050 };
00051 
00052 class Pomdp
00053 {
00054   private:
00055     CMutex execution_mutex;
00056     bool execution_flag;
00057     int actioncount;
00058     std::vector<int> probablestates;
00059 
00060     ros::NodeHandle node_handle_;
00061 
00062     Policy *myPolicy;
00063     
00064     // [publisher attributes]
00065     ros::Publisher focused_obj_label_publisher;
00066     std_msgs::Int32 ObjLabel_msg;
00067     ros::Publisher belief_summary_publisher;
00068     iri_wam_common_msgs::belief_summary belief_summary_msg;
00069     ros::Publisher belief_publisher;
00070     iri_wam_common_msgs::belief belief_msg;
00071 
00072     // [subscriber attributes]
00073         
00074     // [service attributes]
00075     ros::ServiceServer execution_flow_control_server;
00076     bool execution_flow_controlCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00077             
00078     // [client attributes]
00079     ros::ServiceClient obs_client;
00080     iri_wam_common_msgs::obs_request obs_request_srv;
00081     ros::ServiceClient wam_action_client;
00082     iri_wam_common_msgs::wamaction wam_actions_client_srv;
00083             
00084     // [action server attributes]
00085             
00086     // [action client attributes]
00087 
00088     void pomdp_action2wam_action(int pomdp_action, int& wam_action, int& zone, int& hand);
00089     void publish_belief();
00090   public:
00108     Pomdp();
00109 
00122     void mainLoop(void);
00123 
00124 };
00125 #endif
00126 


iri_dummy_pomdp
Author(s): pmonso
autogenerated on Fri Dec 6 2013 21:35:42