00001 00025 #ifndef _ACTION_LAYER_H_ 00026 #define _ACTION_LAYER_H_ 00027 00028 #include <string> 00029 #include <vector> 00030 #include <map> 00031 00032 #include <boost/function.hpp> 00033 00034 #include <ros/ros.h> 00035 #include <ros/callback_queue_interface.h> 00036 00037 #include <mdm_library/ActionSymbol.h> 00038 #include <mdm_library/FactoredSymbolMetadata.h> 00039 00040 00041 00042 namespace mdm_library 00043 { 00053 class ActionLayer 00054 { 00055 public: 00059 typedef std::vector<boost::function<void () > > ActionCallbacksVector; 00063 typedef std::vector<std::string> ActionNamesVector; 00064 00065 typedef std::map<std::string, size_t> ActionIDMap; 00066 00067 typedef std::vector<std::size_t> ActionIDVector; 00068 00074 typedef std::vector<size_t> ActionSizesVector; 00075 00080 ActionLayer (); 00086 ActionLayer ( const FactoredSymbolMetadataConstPtr& action_metadata ); 00087 00092 ActionLayer ( ros::CallbackQueueInterface* queue ); 00093 00095 void actionSymbolCallback ( const mdm_library::ActionSymbolConstPtr& msg ); 00096 00098 void actionMetadataCallback ( const mdm_library::FactoredSymbolMetadataConstPtr& msg ); 00099 00106 void addAction ( boost::function<void () > callback ); 00107 00108 void addAction ( boost::function<void () > callback, const std::string & action_name ); 00109 00110 uint32_t jointToIndividualAction ( const uint32_t joint_action ); 00111 00112 private: 00113 ros::NodeHandle nh_; 00114 00118 ros::Subscriber action_sub_; 00122 ros::Subscriber action_metadata_sub_; 00123 00125 ActionCallbacksVector action_callbacks_; 00127 ActionNamesVector local_action_names_; 00128 ActionIDMap named_action_ids_; 00129 ActionIDVector action_ids_; 00130 00132 ActionSizesVector action_sizes_; 00133 00134 uint32_t cached_sizes_prod_; 00139 ActionSymbolConstPtr pending_action_; 00140 00142 int mdm_agent_index_; 00143 00144 bool using_named_actions_; 00145 }; 00146 } 00147 00148 #endif