runtime_handle.h
Go to the documentation of this file.
00001 
00023 #ifndef RUNTIME_HANDLE_H_
00024 #define RUNTIME_HANDLE_H_
00025 
00026 #include <iostream>
00027 #include <vector>
00028 #include <map>
00029 #include <boost/shared_ptr.hpp>
00030 #include <boost/thread/mutex.hpp>
00031 #include <boost/thread/shared_mutex.hpp>
00032 
00033 #include "micros_swarm/data_type.h"
00034 #include "micros_swarm/listener_helper.h"
00035 #include "micros_swarm/check_neighbor.h"
00036 
00037 namespace micros_swarm{
00038 
00039     class  RuntimeHandle{
00040         public:
00041             RuntimeHandle();
00042             
00043             int getRobotID();
00044             void setRobotID(int robot_id);
00045             
00046             int getRobotType();
00047             void setRobotType(int robot_type);
00048             
00049             int getRobotStatus();
00050             void setRobotStatus(int robot_status);
00051             
00052             const Base& getRobotBase();
00053             void setRobotBase(const Base& robot_base);
00054             void printRobotBase();
00055             
00056             void getNeighbors(std::map<int, NeighborBase>& neighbors);
00057             std::map<int, NeighborBase> getNeighbors();
00058             int getNeighborSize();
00059             bool getNeighborBase(int robot_id, NeighborBase& nb);
00060             void clearNeighbors();
00061             void insertOrUpdateNeighbor(int robot_id, float distance, float azimuth, float elevation, float x, float y, float z, float vx, float vy, float vz);
00062             //delete an neighbor robot according to id
00063             void deleteNeighbor(int robot_id);
00064             bool inNeighbors(int robot_id);
00065             void printNeighbor();
00066             
00067             void insertOrUpdateSwarm(int swarm_id, bool value);
00068             //check if the local robot is in a swarm 
00069             bool getSwarmFlag(int swarm_id);
00070             //get the swarm list of the local robot
00071             void getSwarmList(std::vector<int>& swarm_list);
00072             void deleteSwarm(int swarm_id);
00073             void printSwarm();
00074             
00075             //check if a robot is in a swarm
00076             bool inNeighborSwarm(int robot_id, int swarm_id);
00077             void joinNeighborSwarm(int robot_id, int swarm_id);
00078             void leaveNeighborSwarm(int robot_id, int swarm_id);
00079             void insertOrRefreshNeighborSwarm(int robot_id, const std::vector<int>& swarm_list);
00080             //get the member robot set of a swarm 
00081             void getSwarmMembers(int swarm_id, std::set<int>& swarm_members);
00082             void deleteNeighborSwarm(int robot_id);
00083             void printNeighborSwarm();
00084             
00085             void createVirtualStigmergy(int id);
00086             void insertOrUpdateVirtualStigmergy(int id, const std::string& key, const std::vector<uint8_t>& value, \
00087                                                        unsigned int lclock, time_t wtime, unsigned int rcount, int robot_id);
00088             bool isVirtualStigmergyTupleExist(int id, const std::string& key);
00089             bool getVirtualStigmergyTuple(int id, const std::string& key, VirtualStigmergyTuple& vstig_tuple);
00090             void updateVirtualStigmergyTupleReadCount(int id, const std::string& key, int count);
00091             int getVirtualStigmergySize(int id);
00092             void deleteVirtualStigmergy(int id);
00093             void deleteVirtualStigmergyValue(int id, const std::string& key);
00094             void printVirtualStigmergy();
00095             bool checkNeighborsOverlap(int robot_id);
00096 
00097             void createBlackBoard(int id);
00098             void insertOrUpdateBlackBoard(int id, const std::string& key, const std::vector<uint8_t>& value, const ros::Time& timestamp, int robot_id);
00099             bool isBlackBoardTupleExist(int id, const std::string& key);
00100             void getBlackBoardTuple(int id, const std::string& key, BlackBoardTuple& bb_tuple);
00101             int getBlackBoardSize(int id);
00102             void deleteBlackBoard(int id);
00103             void deleteBlackBoardValue(int id, const std::string& key);
00104             void printBlackBoard();
00105             
00106             const float& getNeighborDistance();
00107             void setNeighborDistance(float neighbor_distance);
00108             
00109             void insertOrUpdateListenerHelper(const std::string& key, const boost::shared_ptr<ListenerHelper> helper);
00110             const boost::shared_ptr<ListenerHelper> getListenerHelper(const std::string& key);
00111             void deleteListenerHelper(const std::string& key);
00112             
00113             void insertBarrier(int robot_id);
00114             int getBarrierSize();
00115 
00116             bool getSCDSPSOValue(const std::string& aKey, SCDSPSODataTuple& aT);
00117             void insertOrUpdateSCDSPSOValue(const std::string& aKey, const SCDSPSODataTuple& aT);
00118 
00119         private:
00120             int robot_id_;
00121             boost::shared_mutex id_mutex_;
00122             int robot_type_;  //TODO
00123             boost::shared_mutex type_mutex_;
00124             int robot_status_;  //TODO
00125             boost::shared_mutex status_mutex_;
00126             Base robot_base_;
00127             boost::shared_mutex base_mutex_;
00128             std::map<int, NeighborBase> neighbors_;
00129             boost::shared_mutex neighbor_mutex_;
00130             std::map<int, bool> swarms_;
00131             boost::shared_mutex swarm_mutex_;
00132             std::map<int, NeighborSwarmTuple> neighbor_swarms_;
00133             boost::shared_mutex neighbor_swarm_mutex_;
00134             std::map<int, std::map<std::string, VirtualStigmergyTuple> > virtual_stigmergy_;
00135             boost::shared_mutex vstig_mutex_;
00136             std::map<int, std::map<std::string, BlackBoardTuple> > blackboard_;
00137             boost::shared_mutex bb_mutex_;
00138             float neighbor_distance_;
00139             boost::shared_mutex neighbor_distance_mutex_;
00140             std::map<std::string, boost::shared_ptr<ListenerHelper> > listener_helpers_;
00141             boost::shared_mutex listener_helpers_mutex_;
00142             std::set<int> barrier_;
00143             boost::shared_mutex barrier_mutex_;
00144             std::map<std::string, SCDSPSODataTuple> scds_pso_tuple_;
00145             boost::shared_mutex scds_pso_tuple_mutex_;
00146             boost::shared_ptr<CheckNeighborInterface> cni_;
00147     };
00148 };
00149 
00150 #endif


micros_swarm
Author(s):
autogenerated on Thu Jun 6 2019 18:52:14