predicate_manager.h
Go to the documentation of this file.
00001 
00025 #ifndef _PREDICATE_MANAGER_H_
00026 #define _PREDICATE_MANAGER_H_
00027 
00028 #include <string>
00029 #include <map>
00030 #include <vector>
00031 
00032 #include <boost/function.hpp>
00033 
00034 #include <ros/ros.h>
00035 
00036 #include <predicate_manager/common_defs.h>
00037 #include <predicate_manager/predicate.h>
00038 #include <predicate_manager/event.h>
00039 
00040 #include <predicate_manager/PredicateInfoMap.h>
00041 #include <predicate_manager/PredicateUpdate.h>
00042 #include <predicate_manager/EventInfoMap.h>
00043 #include <predicate_manager/EventUpdate.h>
00044 
00045 #define MAX_UPDATE_COUNTER 4294967295 ///maximum value for a 32-bit usigned int
00046 
00047 namespace predicate_manager
00048 {
00067 class PredicateManager
00068 {
00069 public:
00071     typedef boost::shared_ptr<std::set<uint32_t> > ObserverPtr;
00073     typedef boost::unordered_map<NameID, ObserverPtr> NameIDObserver;
00075     typedef boost::unordered_map<NrID, ObserverPtr, cantor_pair_hash> NrIDObserver;
00077     typedef boost::unordered_map<NrID, bool, cantor_pair_hash> ValueMap;
00079     typedef std::vector<boost::shared_ptr<Predicate> > PredRefVector; 
00080     typedef std::vector<boost::shared_ptr<Event> > EvRefVector; 
00081 
00083     PredicateManager();
00084 
00090     void spin();
00091 
00097     void addPredicate ( Predicate& p );
00098 
00104     void addEvent ( Event& e );
00105 
00112     void predicateUpdateTrigger ( const NrID pred_nr_id, bool value );
00113 
00118     void eventTrigger ( const uint32_t ev_nr );
00119 
00120 private:
00124     void PMUpdate();
00125 
00132     void consumePredicateMap ( const PredicateInfoMapConstPtr& msg );
00140     void consumePredicateUpdate ( const PredicateUpdateConstPtr& msg );
00144     void publishPredicateMap();
00148     void publishPredicateUpdate();
00152     void publishEventMap();
00156     void publishEventUpdate();
00161     void updateDependants ( const NrID pred_nr_id );
00166     void prepareLocalDependencies();
00173     void setDependencyReferences ( const NrID pred_nr_id, const NameID pred_name_id );
00181     void setNrOfPredicates ( const int pm_id, const std::size_t size );
00182 
00183     ros::NodeHandle nh_;
00184 
00185     bool started_; 
00186     bool any_changed_; 
00187 
00188     uint32_t pm_id_; 
00189     std::vector<std::size_t> nr_of_predicates_; 
00190     std::vector<bool> initialized_pms_; 
00191     double update_period_; 
00192 
00194 
00195     ros::Publisher predicate_maps_pub_; 
00196     ros::Publisher predicate_updates_pub_; 
00197     ros::Subscriber predicate_maps_sub_; 
00198     ros::Subscriber predicate_updates_sub_; 
00199 
00200     std::vector<uint32_t> pred_update_counters_; 
00201     PredRefVector local_pred_refs_; 
00202     ValueMap value_map_; 
00203     ValueMap last_value_map_; 
00204     NameIDSet registered_predicates_; 
00205     NameIDObserver pred_name_observer_; 
00206     NrIDObserver pred_nr_observer_; 
00207 
00209 
00210     ros::Publisher event_maps_pub_;
00211     ros::Publisher event_updates_pub_;
00212 
00213     uint32_t ev_update_counter_; 
00214     EvRefVector local_ev_refs_; 
00215     NameIDSet registered_events_; 
00216     NameIDObserver ev_name_observer_; 
00217     NrIDObserver ev_nr_observer_; 
00218     std::vector<uint32_t> events_to_publish_; 
00219 };
00220 }
00221 
00222 #endif


predicate_manager
Author(s): Joao Reis and Joao Messias
autogenerated on Wed Aug 26 2015 12:28:34