fixed_strategy.h
Go to the documentation of this file.
00001 #ifndef _fixed_strategy_h_
00002 #define _fixed_strategy_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 
00009 #include "mutex.h"
00010 
00011 // [publisher subscriber headers]
00012 
00013 // [service client headers]
00014 #include "std_srvs/Empty.h"
00015 #include "std_msgs/Int32.h"
00016 #include "iri_wam_common_msgs/wamaction.h"
00017 #include "iri_wam_common_msgs/obs_request.h"
00018 
00019 // [action server client headers]
00020 
00021 #define NUMPOSES 3
00022 
00023 enum {
00024     //remember to change the other .h enums (dummy_pomdp)!
00025     FOLDLOW,
00026     FOLDHIGH,
00027     SPREAD,
00028     FLIP,
00029     SHAKE,
00030     CHANGEPILE,
00031     MOVEAWAY,
00032     DUMMY,
00033     TAKE
00034 };
00035 
00036 enum {
00037     STRAIGHT,
00038     ISOMETRIC,
00039     PEG
00040 };
00041 
00042 enum {
00043     ANY,
00044     A,
00045     B
00046 };
00047 
00048 
00049 class FixedStrategy
00050 {
00051   private:
00052     CMutex execution_mutex;
00053     bool execution_flag;
00054 
00055     ros::NodeHandle node_handle_;
00056     
00057     // [publisher attributes]
00058     ros::Publisher focused_obj_label_publisher;
00059     std_msgs::Int32 ObjLabel_msg;
00060 
00061     // [subscriber attributes]
00062         
00063     // [service attributes]
00064     ros::ServiceServer execution_flow_control_server;
00065     bool execution_flow_controlCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00066             
00067     // [client attributes]
00068     ros::ServiceClient obs_client;
00069     iri_wam_common_msgs::obs_request obs_request_srv;
00070     ros::ServiceClient wam_action_client;
00071     iri_wam_common_msgs::wamaction wam_actions_client_srv;
00072             
00073     // [action server attributes]
00074             
00075     // [action client attributes]
00076   public:
00094     FixedStrategy();
00095 
00108     void mainLoop(void);
00109 
00110 };
00111 #endif
00112 


iri_2piles_pomdp
Author(s): pmonso
autogenerated on Fri Dec 6 2013 21:45:26