app2_statistic.cpp
Go to the documentation of this file.
1 
23 #include <iostream>
24 #include <fstream>
25 #include <sstream>
26 #include <ros/ros.h>
27 #include <math.h>
28 
29 #include <boost/function.hpp>
30 #include <boost/bind.hpp>
31 #include <boost/thread.hpp>
32 
33 #include "std_msgs/String.h"
34 #include "nav_msgs/Odometry.h"
35 #include "geometry_msgs/Twist.h"
36 
37 using namespace std;
38 
39 int SWARM_SIZE = 20;
40 int IN_NEI_DIS = 5;
41 int OUT_NEI_DIS = 25;
42 int COM_DIS = 40;
43 
44 struct Position{
45  float x;
46  float y;
47 };
48 
49 float pos_dis(Position self, Position nei)
50 {
51  return sqrt((self.x - nei.x)*(self.x - nei.x) + (self.y - nei.y)*(self.y - nei.y));
52 }
53 
54 std::map<int, Position> pos_map;
55 std::map<int, std::vector<int> > neighbor_map;
56 
57 bool red(int id)
58 {
59  if(id <= 9) {
60  return true;
61  }
62  return false;
63 }
64 
65 bool blue(int id)
66 {
67  if(id >= 10) {
68  return true;
69  }
70  return false;
71 }
72 
73 bool same_swarm(int i, int j)
74 {
75  if(red(i) && red(j)) {
76  return true;
77  }
78  if(blue(i) && blue(j)) {
79  return true;
80  }
81  return false;
82 }
83 
84 void callback(const nav_msgs::OdometryConstPtr &lmsg, int r_id)
85 {
86  Position p;
87  p.x = lmsg->pose.pose.position.x;
88  p.y = lmsg->pose.pose.position.y;
89  std::map<int, Position >::iterator pos_it;
90  pos_it = pos_map.find(r_id);
91  if(pos_it != pos_map.end()) {
92  pos_it->second = p;
93  }
94  else {
95  pos_map.insert(std::pair<int, Position>(r_id, p));
96  }
97 
98  /*Position self = p;
99  Position nei;
100  std::vector<int> neis;
101  std::map<int, Position >::iterator it;
102  for(it = pos_map.begin(); it != pos_map.end(); it++) {
103  if(it->first == r_id) {
104  continue;
105  }
106  else {
107  nei = it->second;
108  if (pos_dis(self, nei) < COM_DIS) {
109  neis.push_back(it->first);
110  }
111  }
112  }
113 
114  std::map<int, std::vector<int> >::iterator nei_it;
115  nei_it = neighbor_map.find(r_id);
116  if(nei_it != neighbor_map.end()) {
117  nei_it->second = neis;
118  }
119  else {
120  neighbor_map.insert(std::pair < int, std::vector < int > > (r_id, neis));
121  }*/
122 }
123 
124 Position get_pos(int r_id)
125 {
126  std::map<int, Position >::iterator it;
127  it = pos_map.find(r_id);
128  if(it != pos_map.end()) {
129  return it->second;
130  }
131 
132  Position p;
133  p.x = 0;
134  p.y = 0;
135  return p;
136 }
137 
138 std::vector<int> get_neighbor(int r_id)
139 {
140  std::map<int, std::vector<int> >::iterator it;
141  it = neighbor_map.find(r_id);
142  if(it != neighbor_map.end()) {
143  return it->second;
144  }
145 
146  std::vector<int> nei;
147  nei.clear();
148  return nei;
149 }
150 
151 float nei_dis(int id1, int id2)
152 {
153  Position p1 = get_pos(id1);
154  Position p2 = get_pos(id2);
155 
156  return pos_dis(p1, p2);
157 }
158 
159 float cal_error()
160 {
161  float err = 0;
162  int count = 0;
163  for(int i = 0; i < SWARM_SIZE; i++) {
164  std::vector<int> nei = get_neighbor(i);
165  for(int j = 0; j < nei.size(); j++) {
166  if(same_swarm(i, nei[j])) {
167  err += abs((nei_dis(i, nei[j]) - IN_NEI_DIS));
168  count++;
169  }
170  else {
171  err += abs((nei_dis(i, nei[j]) - OUT_NEI_DIS));
172  count++;
173  }
174  }
175  }
176 
177  if(count > 0) {
178  return err/count;
179  }
180  else {
181  return -1;
182  }
183 }
184 
185 void process()
186 {
187  while(1) {
188  for (int i = 0; i < SWARM_SIZE; i++) {
189  int r_id = i;
190  Position self = get_pos(i);
191  Position nei;
192  std::vector<int> neis;
193  std::map<int, Position>::iterator it;
194  for (it = pos_map.begin(); it != pos_map.end(); it++) {
195  if (it->first == r_id) {
196  continue;
197  } else {
198  nei = it->second;
199  if (pos_dis(self, nei) < COM_DIS) {
200  neis.push_back(it->first);
201  }
202  }
203  }
204 
205  std::map < int, std::vector < int > > ::iterator nei_it;
206  nei_it = neighbor_map.find(r_id);
207  if (nei_it != neighbor_map.end()) {
208  nei_it->second = neis;
209  } else {
210  neighbor_map.insert(std::pair < int, std::vector < int > > (r_id, neis));
211  }
212  }
213  ros::Duration(0.1).sleep();
214  }
215 }
216 
217 int main(int argc, char** argv)
218 {
219  ros::init(argc, argv, "app2_statistic");
220  ros::NodeHandle nh;
221 
222  std::vector<ros::Subscriber> sub_vec;
223  sub_vec.resize(SWARM_SIZE);
224 
225  for(int i = 0; i < SWARM_SIZE; i++) {
226  stringstream ss;
227  ss<<"/robot_"<<i<<"/base_pose_ground_truth";
228  sub_vec[i] = nh.subscribe<nav_msgs::Odometry>(ss.str(), 1000, boost::bind(callback, _1, i));
229  }
230 
231  ros::Duration(1).sleep();
232 
233  boost::thread* process_thread_ = new boost::thread(process);
234 
235  ofstream file;
236  file.open("app2_statistic.txt");
237 
238  int step = 0;
239  while(ros::ok()) {
240  float err = cal_error();
241  std::cout<<step<<" "<<err<<std::endl;
242  file<<step<<" "<<err<<std::endl;
243  step++;
244  ros::spinOnce();
245  ros::Duration(0.5).sleep();
246  }
247 
248  ros::spin();
249  return 0;
250 }
int main(int argc, char **argv)
std::map< int, std::vector< int > > neighbor_map
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
std::vector< int > get_neighbor(int r_id)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int COM_DIS
float cal_error()
bool red(int id)
float pos_dis(Position self, Position nei)
int IN_NEI_DIS
ROSCPP_DECL bool ok()
int OUT_NEI_DIS
void process()
bool blue(int id)
ROSCPP_DECL void spin()
std::map< int, Position > pos_map
void callback(const nav_msgs::OdometryConstPtr &lmsg, int r_id)
float nei_dis(int id1, int id2)
ROSCPP_DECL void spinOnce()
Position get_pos(int r_id)
int SWARM_SIZE
bool same_swarm(int i, int j)


test_statistic
Author(s):
autogenerated on Mon Jun 10 2019 14:02:29