pomdp_modeler.cpp
Go to the documentation of this file.
00001 #include "pomdp_modeler.h"
00002 
00003 PomdpModeler::PomdpModeler(){
00004 
00005   //init class attributes if necessary
00006   this->experiments_per_action = 20;
00007 
00008   this->modelactions = 2*2;
00009   //this->modelactions = 2*3*5;
00010   if (!this->node_handle_.getParam("/pomdp_planner/numactions", numactions)){
00011     //this->numactions = 3*2*6; // hand (3) / zone (2) / actions (6)
00012     this->numactions = 2*2*3; // hand (2) / zone (2) / actions (3)
00013     //this->node_handle_.setParam("/pompd_planner/numstates",numactions);
00014   }
00015   if (!this->node_handle_.getParam("/pomdp_planner/numstates", numstates)){
00016     this->numstates = 5*5*2; // pilea (5) / pileb (5) / wrinkle (2)
00017     //this->node_handle_.setParam("/pompd_planner/numstates",numstates);
00018   }
00019   if (!this->node_handle_.getParam("/pomdp_planner/numobservations", numobservations)){
00020     this->numobservations = 5*5; // pilea (5) / pileb (5)
00021     //this->node_handle_.setParam("/pompd_planner/numobservations",numobservations);
00022   }
00023 
00024   std::string pomdpfile("data/pomdpfile.txt");
00025   if(node_handle_.getParam("/pomdp_planner/pomdpfile", pomdpfile)) {
00026     ROS_INFO("pomdpfile global path found, using %s", pomdpfile.c_str());
00027   }else{
00028     ROS_WARN("pomdpfile global path not found, using default %s", pomdpfile.c_str());
00029   }
00030 
00031     ROS_INFO("Creating modeler with %d states %d actions %d observations", this->numactions, this->numstates, this->numobservations);
00032     this->modeler = new Modeler(pomdpfile,this->numactions,this->numstates,this->numobservations);
00033 
00034   //init class attributes if necessary
00035   this->execution_flag = false;
00036 
00037   //string for port names
00038 
00039   // [init publishers]
00040   this->focused_obj_label_publisher = this->node_handle_.advertise<std_msgs::Int32>("/planner/focused_obj_label", 5);
00041   
00042   // [init subscribers]
00043   
00044   // [init services]
00045   this->execution_flow_control_server = this->node_handle_.advertiseService("/planner/execution_flow_control", &PomdpModeler::execution_flow_controlCallback, this);
00046   
00047   // [init clients]
00048   obs_client = this->node_handle_.serviceClient<iri_wam_common_msgs::obs_request>("/planner/obs_client");
00049   save_pcl_client = this->node_handle_.serviceClient<iri_wam_common_msgs::wamaction>("/planner/save_pcl");
00050   wam_action_client = this->node_handle_.serviceClient<iri_wam_common_msgs::wamaction>("/planner/wam_action");
00051 
00052   // [init action servers]
00053   
00054   // [init action clients]
00055 
00056     ROS_INFO("Done. Awaiting state family trigger.");
00057 }
00058 
00059 void PomdpModeler::mainLoop(void){
00060 
00061     if(execution_flag){
00062 
00063         //request action
00064         int action = this->counter/this->experiments_per_action;
00065         int hand = action/2;
00066         action = action%2;
00067         ROS_INFO("Requesting action %d with hand %d", action, hand);
00068         wam_actions_client_srv.request.action = action;
00069         wam_actions_client_srv.request.zone = 1;
00070         wam_actions_client_srv.request.hand = hand;
00071         if(wam_action_client.call(wam_actions_client_srv)) 
00072         { 
00073           ROS_INFO("Service result: %d", wam_actions_client_srv.response.success); 
00074         } else { 
00075           ROS_ERROR("Failed to call service wam actions service"); 
00076           return;
00077         } 
00078         //request observation
00079         ROS_INFO("Requesting observation");
00080 #ifdef REAL_OBS
00081         if(obs_client.call(obs_request_srv)) 
00082         { 
00083           ROS_INFO("Service result: %d", obs_request_srv.response.num_objects); 
00084         } else { 
00085           ROS_ERROR("Failed to call service observation client"); 
00086           return;
00087         }
00088         //publish current model progress
00089         //TODO state_final when on a familiy state has many equivalent candidates
00090         ROS_INFO("Adding Observation %d %d", obs_request_srv.response.num_objectsA, obs_request_srv.response.num_objectsB);
00091         //this->modeler->addObservationExperienced(action, state_final, obs_request_srv.response.num_objectsA, obs_request_srv.response.num_objectsB);
00092         this->obs_base_matrix[this->real_num_objects][obs_request_srv.response.num_objectsA]++; 
00093 #else
00094         if(save_pcl_client.call(wam_actions_client_srv)) 
00095         { 
00096           ROS_INFO("Service result: %d", obs_request_srv.response.num_objects); 
00097         } else { 
00098           ROS_ERROR("Failed to call service observation client at action %d base state %d and counter %d",action, this->real_num_objects, this->counter); 
00099           return;
00100         }
00101 #endif
00102         this->progress_msg.data = 1;
00103         ROS_INFO("Action %d %d %% completed [Total: %d %%]", action, (this->counter%this->experiments_per_action)*100/this->experiments_per_action, this->counter*100/(this->experiments_per_action*this->numactions));
00104         focused_obj_label_publisher.publish(this->progress_msg);
00105         this->counter++;
00106         if(this->counter == this->experiments_per_action*this->modelactions){
00107             ROS_INFO("All experiments completed. Awaiting next state family.");
00108             this->execution_flag = false;
00109         }
00110     }
00111 }
00112 
00113 //ad-hoc
00114 //void PomdpModeler::copyStateFamilies(){
00115 //    int numa, numb;
00116 //    int unique_acts = (this->numactions-1)/2;
00117 //    int equi_state;
00118 //    for(int state_final=5;state_final<numstates;state_final++){
00119 //        for(int act=0;act<unique_acts;act++){
00120 //            for(int obs=0;obs<numobservations;obs++){
00121 //               equi_state = modeler->get_equivalent_base_state(state_final);
00122 //               modeler->setObservationProbability(act,state_final,obs,modeler->getObservationProbability(act,equi_state,obs)); 
00123 //               //copy to equivalent actions, we need to swap observations!
00124 //               modeler->get_num_obj(state_final,numa,numb,NUMMAX);
00125 //               modeler->setObservationProbability(act+unique_acts,state_final,obs,obs_base_matrix[numa][numb]); 
00126 //            }
00127 //        }
00128 //    }
00129 //}
00130 
00131 bool PomdpModeler::execution_flow_controlCallback(iri_wam_common_msgs::modeling::Request &req, iri_wam_common_msgs::modeling::Response &res){
00132 
00133     //TODO model matrix backup
00134     //reset auxiliary values:
00135     this->counter = 0;
00136     this->real_num_objects = req.stateFamily;
00137     //resume execution
00138     this->execution_flag = true;
00139     return true; 
00140 }
00141 
00142 void PomdpModeler::printObsBaseMatrix(){
00143     std::stringstream strs(std::stringstream::in);
00144     for(int i=0; i<5; i++){
00145         for(int j=0; j<5; j++){
00146             strs << obs_base_matrix[i][j] << " ";
00147         }
00148         strs << std::endl;
00149     }
00150     ROS_INFO("Matrix\n %s",strs.str().c_str()); 
00151 }
00152 
00153 /* main function */
00154 int main(int argc,char *argv[])
00155 {
00156     ros::init(argc, argv, "pomdp_modeler");
00157     PomdpModeler pomdp_modeler;
00158     ros::Rate loop_rate(10); 
00159     while(ros::ok()){
00160       pomdp_modeler.mainLoop();
00161       ros::spinOnce();
00162       loop_rate.sleep(); 
00163     }
00164 }


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