testrth.cpp
Go to the documentation of this file.
1 
23 #include <ros/ros.h>
25 
26 using namespace micros_swarm;
27 
28 int main(int argc, char** argv)
29 {
30  ros::init(argc, argv, "micros_swarm_framework_main_node");
31  ros::NodeHandle nh;
32 
33  RuntimeHandle rth;
34  rth.setRobotID(1);
35 
36  Base base(1,1,1,2,2,2,1);
37  rth.setRobotBase(base);
38  rth.printRobotBase();
39  std::cout<<std::endl;
40 
41  rth.insertOrUpdateNeighbor(2, 0, 0, 0, 1, 1, 1,2, 2, 2);
42  rth.insertOrUpdateNeighbor(3, 1, 2, 3, 2, 2, 2,3, 3, 3);
43  rth.insertOrUpdateNeighbor(4, 2, 2, 2, 1, 2, 3,3, 3, 3);
44  rth.printNeighbor();
45  std::cout<<"------"<<std::endl;
46  rth.insertOrUpdateNeighbor(2, 1, 2, 3, 4, 5, 6,7, 8, 9);
47  rth.deleteNeighbor(3);
48  rth.deleteNeighbor(16);
49  rth.printNeighbor();
50  std::cout<<std::endl;
51 
52  rth.insertOrUpdateSwarm(1, true);
53  rth.insertOrUpdateSwarm(2, false);
54  rth.insertOrUpdateSwarm(3, true);
55  rth.printSwarm();
56  std::cout<<"------"<<std::endl;
57  rth.insertOrUpdateSwarm(2, true);
58  rth.deleteSwarm(1);
59  rth.deleteSwarm(16);
60  rth.printSwarm();
61  std::cout<<rth.getSwarmFlag(1)<<std::endl;
62  std::cout<<rth.getSwarmFlag(2)<<std::endl;
63  std::cout<<std::endl;
64 
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);
70  rth.printNeighborSwarm();
71  std::cout<<rth.inNeighborSwarm(2, 2)<<std::endl;
72  std::cout<<rth.inNeighborSwarm(2, 4)<<std::endl;
73  std::cout<<rth.inNeighborSwarm(3, 5)<<std::endl;
74  std::cout<<rth.inNeighborSwarm(3, 1)<<std::endl;
75  std::cout<<"------"<<std::endl;
76  rth.joinNeighborSwarm(2, 4);
77  rth.joinNeighborSwarm(2, 5);
78  rth.leaveNeighborSwarm(2, 2);
79  rth.leaveNeighborSwarm(2, 3);
80  rth.leaveNeighborSwarm(2, 17);
81  rth.printNeighborSwarm();
82  std::cout<<"------"<<std::endl;
83  rth.deleteNeighborSwarm(2);
84  rth.deleteNeighborSwarm(9);
85  rth.printNeighborSwarm();
86  std::cout<<std::endl;
87 
90  std::vector<uint8_t> val1;
91  val1.push_back(1);
92  rth.insertOrUpdateVirtualStigmergy(1, "key1", val1, 1, time(0), 0, 1);
93  std::vector<uint8_t> val2;
94  val2.push_back(2);
95  rth.insertOrUpdateVirtualStigmergy(1, "key2", val2, 1, time(0), 0, 1);
96  std::vector<uint8_t> val3;
97  val3.push_back(3);
98  rth.insertOrUpdateVirtualStigmergy(1, "key3", val3, 1, time(0), 0, 1);
101  rth.getVirtualStigmergyTuple(1, "key2", vst1);
102  vst1.print();
104  rth.getVirtualStigmergyTuple(2, "key3", vst2);
105  vst2.print();
106  std::cout<<rth.getVirtualStigmergySize(1)<<std::endl;;
107  std::cout<<rth.getVirtualStigmergySize(2)<<std::endl;
108  rth.deleteVirtualStigmergyValue(1, "key2");
109  rth.deleteVirtualStigmergyValue(1, "key6");
110  rth.deleteVirtualStigmergyValue(2, "key3");
111  rth.deleteVirtualStigmergyValue(5, "key7");
112  rth.printVirtualStigmergy();
114  rth.getVirtualStigmergyTuple(2, "key7", vst3);
115  vst3.print();
117  rth.getVirtualStigmergyTuple(7, "key11", vst4);
118  vst4.print();
119  rth.deleteVirtualStigmergy(2);
120  rth.deleteVirtualStigmergy(5);
121  rth.printVirtualStigmergy();
122 
123  ros::spin();
124  return 0;
125 }
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 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)
bool getSwarmFlag(int swarm_id)
ROSCPP_DECL void spin()
void insertOrRefreshNeighborSwarm(int robot_id, const std::vector< int > &swarm_list)
int main(int argc, char **argv)
Definition: testrth.cpp:28
void leaveNeighborSwarm(int robot_id, int swarm_id)
void deleteVirtualStigmergy(int id)
void deleteVirtualStigmergyValue(int id, const std::string &key)


testrth
Author(s):
autogenerated on Mon Jun 10 2019 14:02:34