runtime_handle.h
Go to the documentation of this file.
1 
23 #ifndef RUNTIME_HANDLE_H_
24 #define RUNTIME_HANDLE_H_
25 
26 #include <iostream>
27 #include <vector>
28 #include <map>
29 #include <boost/shared_ptr.hpp>
30 #include <boost/thread/mutex.hpp>
31 #include <boost/thread/shared_mutex.hpp>
32 
33 #include "micros_swarm/data_type.h"
36 
37 namespace micros_swarm{
38 
40  public:
41  RuntimeHandle();
42 
43  int getRobotID();
44  void setRobotID(int robot_id);
45 
46  int getRobotType();
47  void setRobotType(int robot_type);
48 
49  int getRobotStatus();
50  void setRobotStatus(int robot_status);
51 
52  const Base& getRobotBase();
53  void setRobotBase(const Base& robot_base);
54  void printRobotBase();
55 
56  void getNeighbors(std::map<int, NeighborBase>& neighbors);
57  std::map<int, NeighborBase> getNeighbors();
58  int getNeighborSize();
59  bool getNeighborBase(int robot_id, NeighborBase& nb);
60  void clearNeighbors();
61  void insertOrUpdateNeighbor(int robot_id, float distance, float azimuth, float elevation, float x, float y, float z, float vx, float vy, float vz);
62  //delete an neighbor robot according to id
63  void deleteNeighbor(int robot_id);
64  bool inNeighbors(int robot_id);
65  void printNeighbor();
66 
67  void insertOrUpdateSwarm(int swarm_id, bool value);
68  //check if the local robot is in a swarm
69  bool getSwarmFlag(int swarm_id);
70  //get the swarm list of the local robot
71  void getSwarmList(std::vector<int>& swarm_list);
72  void deleteSwarm(int swarm_id);
73  void printSwarm();
74 
75  //check if a robot is in a swarm
76  bool inNeighborSwarm(int robot_id, int swarm_id);
77  void joinNeighborSwarm(int robot_id, int swarm_id);
78  void leaveNeighborSwarm(int robot_id, int swarm_id);
79  void insertOrRefreshNeighborSwarm(int robot_id, const std::vector<int>& swarm_list);
80  //get the member robot set of a swarm
81  void getSwarmMembers(int swarm_id, std::set<int>& swarm_members);
82  void deleteNeighborSwarm(int robot_id);
83  void printNeighborSwarm();
84 
85  void createVirtualStigmergy(int id);
86  void insertOrUpdateVirtualStigmergy(int id, const std::string& key, const std::vector<uint8_t>& value, \
87  unsigned int lclock, time_t wtime, unsigned int rcount, int robot_id);
88  bool isVirtualStigmergyTupleExist(int id, const std::string& key);
89  bool getVirtualStigmergyTuple(int id, const std::string& key, VirtualStigmergyTuple& vstig_tuple);
90  void updateVirtualStigmergyTupleReadCount(int id, const std::string& key, int count);
91  int getVirtualStigmergySize(int id);
92  void deleteVirtualStigmergy(int id);
93  void deleteVirtualStigmergyValue(int id, const std::string& key);
94  void printVirtualStigmergy();
95  bool checkNeighborsOverlap(int robot_id);
96 
97  void createBlackBoard(int id);
98  void insertOrUpdateBlackBoard(int id, const std::string& key, const std::vector<uint8_t>& value, const ros::Time& timestamp, int robot_id);
99  bool isBlackBoardTupleExist(int id, const std::string& key);
100  void getBlackBoardTuple(int id, const std::string& key, BlackBoardTuple& bb_tuple);
101  int getBlackBoardSize(int id);
102  void deleteBlackBoard(int id);
103  void deleteBlackBoardValue(int id, const std::string& key);
104  void printBlackBoard();
105 
106  const float& getNeighborDistance();
107  void setNeighborDistance(float neighbor_distance);
108 
109  void insertOrUpdateListenerHelper(const std::string& key, const boost::shared_ptr<ListenerHelper> helper);
110  const boost::shared_ptr<ListenerHelper> getListenerHelper(const std::string& key);
111  void deleteListenerHelper(const std::string& key);
112 
113  void insertBarrier(int robot_id);
114  int getBarrierSize();
115 
116  bool getSCDSPSOValue(const std::string& aKey, SCDSPSODataTuple& aT);
117  void insertOrUpdateSCDSPSOValue(const std::string& aKey, const SCDSPSODataTuple& aT);
118 
119  private:
121  boost::shared_mutex id_mutex_;
122  int robot_type_; //TODO
123  boost::shared_mutex type_mutex_;
124  int robot_status_; //TODO
125  boost::shared_mutex status_mutex_;
127  boost::shared_mutex base_mutex_;
128  std::map<int, NeighborBase> neighbors_;
129  boost::shared_mutex neighbor_mutex_;
130  std::map<int, bool> swarms_;
131  boost::shared_mutex swarm_mutex_;
132  std::map<int, NeighborSwarmTuple> neighbor_swarms_;
133  boost::shared_mutex neighbor_swarm_mutex_;
134  std::map<int, std::map<std::string, VirtualStigmergyTuple> > virtual_stigmergy_;
135  boost::shared_mutex vstig_mutex_;
136  std::map<int, std::map<std::string, BlackBoardTuple> > blackboard_;
137  boost::shared_mutex bb_mutex_;
139  boost::shared_mutex neighbor_distance_mutex_;
140  std::map<std::string, boost::shared_ptr<ListenerHelper> > listener_helpers_;
141  boost::shared_mutex listener_helpers_mutex_;
142  std::set<int> barrier_;
143  boost::shared_mutex barrier_mutex_;
144  std::map<std::string, SCDSPSODataTuple> scds_pso_tuple_;
145  boost::shared_mutex scds_pso_tuple_mutex_;
147  };
148 };
149 
150 #endif
boost::shared_mutex status_mutex_
boost::shared_mutex type_mutex_
std::map< int, std::map< std::string, BlackBoardTuple > > blackboard_
bool isBlackBoardTupleExist(int id, const std::string &key)
void setRobotType(int robot_type)
boost::shared_mutex bb_mutex_
void joinNeighborSwarm(int robot_id, int swarm_id)
void getSwarmList(std::vector< int > &swarm_list)
boost::shared_mutex neighbor_distance_mutex_
std::map< std::string, SCDSPSODataTuple > scds_pso_tuple_
bool checkNeighborsOverlap(int robot_id)
bool getVirtualStigmergyTuple(int id, const std::string &key, VirtualStigmergyTuple &vstig_tuple)
void setRobotID(int robot_id)
void deleteBlackBoardValue(int id, const std::string &key)
bool getNeighborBase(int robot_id, NeighborBase &nb)
void deleteNeighborSwarm(int robot_id)
boost::shared_mutex neighbor_mutex_
void setRobotBase(const Base &robot_base)
void setNeighborDistance(float neighbor_distance)
void insertOrUpdateNeighbor(int robot_id, float distance, float azimuth, float elevation, float x, float y, float z, float vx, float vy, float vz)
void insertOrUpdateSwarm(int swarm_id, bool value)
void deleteSwarm(int swarm_id)
void insertOrUpdateVirtualStigmergy(int id, const std::string &key, const std::vector< uint8_t > &value, unsigned int lclock, time_t wtime, unsigned int rcount, int robot_id)
boost::shared_mutex scds_pso_tuple_mutex_
boost::shared_mutex barrier_mutex_
void insertOrUpdateListenerHelper(const std::string &key, const boost::shared_ptr< ListenerHelper > helper)
bool inNeighbors(int robot_id)
bool inNeighborSwarm(int robot_id, int swarm_id)
boost::shared_mutex vstig_mutex_
void deleteNeighbor(int robot_id)
const float & getNeighborDistance()
void insertOrUpdateBlackBoard(int id, const std::string &key, const std::vector< uint8_t > &value, const ros::Time &timestamp, int robot_id)
const boost::shared_ptr< ListenerHelper > getListenerHelper(const std::string &key)
bool getSwarmFlag(int swarm_id)
boost::shared_mutex listener_helpers_mutex_
void setRobotStatus(int robot_status)
std::map< int, NeighborSwarmTuple > neighbor_swarms_
void deleteListenerHelper(const std::string &key)
boost::shared_ptr< CheckNeighborInterface > cni_
std::map< int, bool > swarms_
void insertOrRefreshNeighborSwarm(int robot_id, const std::vector< int > &swarm_list)
std::map< int, NeighborBase > neighbors_
void getSwarmMembers(int swarm_id, std::set< int > &swarm_members)
boost::shared_mutex swarm_mutex_
boost::shared_mutex id_mutex_
std::map< int, std::map< std::string, VirtualStigmergyTuple > > virtual_stigmergy_
void leaveNeighborSwarm(int robot_id, int swarm_id)
std::map< int, NeighborBase > getNeighbors()
boost::shared_mutex base_mutex_
boost::shared_mutex neighbor_swarm_mutex_
void updateVirtualStigmergyTupleReadCount(int id, const std::string &key, int count)
void deleteVirtualStigmergyValue(int id, const std::string &key)
bool isVirtualStigmergyTupleExist(int id, const std::string &key)
void getBlackBoardTuple(int id, const std::string &key, BlackBoardTuple &bb_tuple)
void insertOrUpdateSCDSPSOValue(const std::string &aKey, const SCDSPSODataTuple &aT)
void insertBarrier(int robot_id)
std::map< std::string, boost::shared_ptr< ListenerHelper > > listener_helpers_
bool getSCDSPSOValue(const std::string &aKey, SCDSPSODataTuple &aT)


micros_swarm
Author(s):
autogenerated on Mon Jun 10 2019 14:02:06