00001 #ifndef _pomdp_modeler_h_ 00002 #define _pomdp_modeler_h_ 00003 00004 #include <iostream> 00005 #include <sstream> 00006 00007 #include "ros/this_node.h" 00008 #include "ros/names.h" 00009 #include "ros/node_handle.h" 00010 #include "ros/rate.h" 00011 00012 #include "mutex.h" 00013 #include "Modeler2piles.h" 00014 00015 // [publisher subscriber headers] 00016 00017 // [service client headers] 00018 #include "std_srvs/Empty.h" 00019 #include "std_msgs/Int32.h" 00020 #include "iri_wam_common_msgs/wamaction.h" 00021 #include "iri_wam_common_msgs/obs_request.h" 00022 #include "iri_wam_common_msgs/modeling.h" 00023 00024 // [action server client headers] 00025 00026 #define NUMMAX 5 00027 00028 class PomdpModeler 00029 { 00030 private: 00031 bool execution_flag; 00032 00033 ros::NodeHandle node_handle_; 00034 00035 // [publisher attributes] 00036 ros::Publisher focused_obj_label_publisher; 00037 std_msgs::Int32 progress_msg; 00038 00039 // [subscriber attributes] 00040 00041 // [service attributes] 00042 ros::ServiceServer execution_flow_control_server; 00043 bool execution_flow_controlCallback(iri_wam_common_msgs::modeling::Request &req, iri_wam_common_msgs::modeling::Response &res); 00044 00045 00046 // [client attributes] 00047 ros::ServiceClient obs_client; 00048 iri_wam_common_msgs::obs_request obs_request_srv; 00049 ros::ServiceClient save_pcl_client; 00050 std_srvs::Empty save_pcl_srv; 00051 ros::ServiceClient wam_action_client; 00052 iri_wam_common_msgs::wamaction wam_actions_client_srv; 00053 00054 // [action server attributes] 00055 00056 // [action client attributes] 00057 00058 //put inside modeler 00059 // std::vector<std::vector<double> > rewardMatrix; // double rewardMatrix[NUMACTIONS][NUMSTATES]; 00060 // array3d transform; // double transform[NUMACTIONS][NUMSTATES][NUMSTATES]; 00061 // array3d observations; // double observations[NUMACTIONS][NUMSTATES][NUMOBSERVATIONS]; 00062 double obs_base_matrix[5][5]; 00063 00064 Modeler2piles *modeler; 00065 int experiments_per_action; 00066 // void copyStateFamilies(); 00067 int numactions; 00068 int modelactions; 00069 int numstates; 00070 int numobservations; 00071 00072 int counter; 00073 int state_final; 00074 int real_num_objects; 00075 void printObsBaseMatrix(); 00076 00077 public: 00095 PomdpModeler(); 00096 00109 void mainLoop(void); 00110 00111 }; 00112 #endif 00113