Go to the documentation of this file.00001
00023 #include <iostream>
00024 #include <fstream>
00025 #include <sstream>
00026 #include <ros/ros.h>
00027 #include <math.h>
00028
00029 #include <boost/function.hpp>
00030 #include <boost/bind.hpp>
00031 #include <boost/thread.hpp>
00032
00033 #include "std_msgs/String.h"
00034 #include "nav_msgs/Odometry.h"
00035 #include "geometry_msgs/Twist.h"
00036
00037 using namespace std;
00038
00039 int SWARM_SIZE = 20;
00040 int IN_NEI_DIS = 5;
00041 int OUT_NEI_DIS = 25;
00042 int COM_DIS = 40;
00043
00044 struct Position{
00045 float x;
00046 float y;
00047 };
00048
00049 float pos_dis(Position self, Position nei)
00050 {
00051 return sqrt((self.x - nei.x)*(self.x - nei.x) + (self.y - nei.y)*(self.y - nei.y));
00052 }
00053
00054 std::map<int, Position> pos_map;
00055 std::map<int, std::vector<int> > neighbor_map;
00056
00057 bool red(int id)
00058 {
00059 if(id <= 9) {
00060 return true;
00061 }
00062 return false;
00063 }
00064
00065 bool blue(int id)
00066 {
00067 if(id >= 10) {
00068 return true;
00069 }
00070 return false;
00071 }
00072
00073 bool same_swarm(int i, int j)
00074 {
00075 if(red(i) && red(j)) {
00076 return true;
00077 }
00078 if(blue(i) && blue(j)) {
00079 return true;
00080 }
00081 return false;
00082 }
00083
00084 void callback(const nav_msgs::OdometryConstPtr &lmsg, int r_id)
00085 {
00086 Position p;
00087 p.x = lmsg->pose.pose.position.x;
00088 p.y = lmsg->pose.pose.position.y;
00089 std::map<int, Position >::iterator pos_it;
00090 pos_it = pos_map.find(r_id);
00091 if(pos_it != pos_map.end()) {
00092 pos_it->second = p;
00093 }
00094 else {
00095 pos_map.insert(std::pair<int, Position>(r_id, p));
00096 }
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122 }
00123
00124 Position get_pos(int r_id)
00125 {
00126 std::map<int, Position >::iterator it;
00127 it = pos_map.find(r_id);
00128 if(it != pos_map.end()) {
00129 return it->second;
00130 }
00131
00132 Position p;
00133 p.x = 0;
00134 p.y = 0;
00135 return p;
00136 }
00137
00138 std::vector<int> get_neighbor(int r_id)
00139 {
00140 std::map<int, std::vector<int> >::iterator it;
00141 it = neighbor_map.find(r_id);
00142 if(it != neighbor_map.end()) {
00143 return it->second;
00144 }
00145
00146 std::vector<int> nei;
00147 nei.clear();
00148 return nei;
00149 }
00150
00151 float nei_dis(int id1, int id2)
00152 {
00153 Position p1 = get_pos(id1);
00154 Position p2 = get_pos(id2);
00155
00156 return pos_dis(p1, p2);
00157 }
00158
00159 float cal_error()
00160 {
00161 float err = 0;
00162 int count = 0;
00163 for(int i = 0; i < SWARM_SIZE; i++) {
00164 std::vector<int> nei = get_neighbor(i);
00165 for(int j = 0; j < nei.size(); j++) {
00166 if(same_swarm(i, nei[j])) {
00167 err += abs((nei_dis(i, nei[j]) - IN_NEI_DIS));
00168 count++;
00169 }
00170 else {
00171 err += abs((nei_dis(i, nei[j]) - OUT_NEI_DIS));
00172 count++;
00173 }
00174 }
00175 }
00176
00177 if(count > 0) {
00178 return err/count;
00179 }
00180 else {
00181 return -1;
00182 }
00183 }
00184
00185 void process()
00186 {
00187 while(1) {
00188 for (int i = 0; i < SWARM_SIZE; i++) {
00189 int r_id = i;
00190 Position self = get_pos(i);
00191 Position nei;
00192 std::vector<int> neis;
00193 std::map<int, Position>::iterator it;
00194 for (it = pos_map.begin(); it != pos_map.end(); it++) {
00195 if (it->first == r_id) {
00196 continue;
00197 } else {
00198 nei = it->second;
00199 if (pos_dis(self, nei) < COM_DIS) {
00200 neis.push_back(it->first);
00201 }
00202 }
00203 }
00204
00205 std::map < int, std::vector < int > > ::iterator nei_it;
00206 nei_it = neighbor_map.find(r_id);
00207 if (nei_it != neighbor_map.end()) {
00208 nei_it->second = neis;
00209 } else {
00210 neighbor_map.insert(std::pair < int, std::vector < int > > (r_id, neis));
00211 }
00212 }
00213 ros::Duration(0.1).sleep();
00214 }
00215 }
00216
00217 int main(int argc, char** argv)
00218 {
00219 ros::init(argc, argv, "app2_statistic");
00220 ros::NodeHandle nh;
00221
00222 std::vector<ros::Subscriber> sub_vec;
00223 sub_vec.resize(SWARM_SIZE);
00224
00225 for(int i = 0; i < SWARM_SIZE; i++) {
00226 stringstream ss;
00227 ss<<"/robot_"<<i<<"/base_pose_ground_truth";
00228 sub_vec[i] = nh.subscribe<nav_msgs::Odometry>(ss.str(), 1000, boost::bind(callback, _1, i));
00229 }
00230
00231 ros::Duration(1).sleep();
00232
00233 boost::thread* process_thread_ = new boost::thread(process);
00234
00235 ofstream file;
00236 file.open("app2_statistic.txt");
00237
00238 int step = 0;
00239 while(ros::ok()) {
00240 float err = cal_error();
00241 std::cout<<step<<" "<<err<<std::endl;
00242 file<<step<<" "<<err<<std::endl;
00243 step++;
00244 ros::spinOnce();
00245 ros::Duration(0.5).sleep();
00246 }
00247
00248 ros::spin();
00249 return 0;
00250 }