28 int main(
int argc,
char** argv)
30 ros::init(argc, argv,
"micros_swarm_framework_main_node");
36 Base base(1,1,1,2,2,2,1);
45 std::cout<<
"------"<<std::endl;
56 std::cout<<
"------"<<std::endl;
65 std::vector<int> s1, s2;
66 s1.push_back(1); s1.push_back(2); s1.push_back(3);
67 s2.push_back(4); s2.push_back(5); s2.push_back(6);
75 std::cout<<
"------"<<std::endl;
82 std::cout<<
"------"<<std::endl;
90 std::vector<uint8_t> val1;
93 std::vector<uint8_t> val2;
96 std::vector<uint8_t> val3;
void joinNeighborSwarm(int robot_id, int swarm_id)
void createVirtualStigmergy(int id)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int getVirtualStigmergySize(int id)
bool getVirtualStigmergyTuple(int id, const std::string &key, VirtualStigmergyTuple &vstig_tuple)
void setRobotID(int robot_id)
void printNeighborSwarm()
void deleteNeighborSwarm(int robot_id)
void setRobotBase(const Base &robot_base)
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)
bool inNeighborSwarm(int robot_id, int swarm_id)
void deleteNeighbor(int robot_id)
void printVirtualStigmergy()
bool getSwarmFlag(int swarm_id)
void insertOrRefreshNeighborSwarm(int robot_id, const std::vector< int > &swarm_list)
int main(int argc, char **argv)
void leaveNeighborSwarm(int robot_id, int swarm_id)
void deleteVirtualStigmergy(int id)
void deleteVirtualStigmergyValue(int id, const std::string &key)