app1_statistic.cpp
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 NEI_DIS = 7;
00041 int COM_DIS = 8;
00042 
00043 struct Position{
00044     float x;
00045     float y;
00046 };
00047 
00048 float pos_dis(Position self, Position nei)
00049 {
00050     return sqrt((self.x - nei.x)*(self.x - nei.x) + (self.y - nei.y)*(self.y - nei.y));
00051 }
00052 
00053 std::map<int, Position> pos_map;
00054 std::map<int, std::vector<int> > neighbor_map;
00055 
00056 void callback(const nav_msgs::OdometryConstPtr &lmsg, int r_id)
00057 {
00058     Position p;
00059     p.x = lmsg->pose.pose.position.x;
00060     p.y = lmsg->pose.pose.position.y;
00061     std::map<int, Position >::iterator pos_it;
00062     pos_it = pos_map.find(r_id);
00063     if(pos_it != pos_map.end()) {
00064         pos_it->second = p;
00065     }
00066     else {
00067         pos_map.insert(std::pair<int, Position>(r_id, p));
00068     }
00069 
00070     /*Position self = p;
00071     Position nei;
00072     std::vector<int> neis;
00073     std::map<int, Position >::iterator it;
00074     for(it = pos_map.begin(); it != pos_map.end(); it++) {
00075         if(it->first == r_id) {
00076             continue;
00077         }
00078         else {
00079             nei = it->second;
00080             if (pos_dis(self, nei) < COM_DIS) {
00081                 neis.push_back(it->first);
00082             }
00083         }
00084     }
00085 
00086     std::map<int, std::vector<int> >::iterator nei_it;
00087     nei_it = neighbor_map.find(r_id);
00088     if(nei_it != neighbor_map.end()) {
00089         nei_it->second = neis;
00090     }
00091     else {
00092         neighbor_map.insert(std::pair < int, std::vector < int > > (r_id, neis));
00093     }*/
00094 }
00095 
00096 Position get_pos(int r_id)
00097 {
00098     std::map<int, Position >::iterator it;
00099     it = pos_map.find(r_id);
00100     if(it != pos_map.end()) {
00101         return it->second;
00102     }
00103 
00104     Position p;
00105     p.x = 0;
00106     p.y = 0;
00107     return  p;
00108 }
00109 
00110 std::vector<int> get_neighbor(int r_id)
00111 {
00112     std::map<int, std::vector<int> >::iterator it;
00113     it = neighbor_map.find(r_id);
00114     if(it != neighbor_map.end()) {
00115         return it->second;
00116     }
00117 
00118     std::vector<int> nei;
00119     nei.clear();
00120     return  nei;
00121 }
00122 
00123 float nei_dis(int id1, int id2)
00124 {
00125     Position p1 = get_pos(id1);
00126     Position p2 = get_pos(id2);
00127 
00128     return pos_dis(p1, p2);
00129 }
00130 
00131 float cal_error()
00132 {
00133     float err = 0;
00134     int count = 0;
00135     for(int i = 0; i < SWARM_SIZE; i++) {
00136         std::vector<int> nei = get_neighbor(i);
00137         for(int j = 0; j < nei.size(); j++) {
00138             err += abs((nei_dis(i, nei[j]) - NEI_DIS));
00139             count++;
00140         }
00141     }
00142 
00143     if(count > 0) {
00144         return err/count;
00145     }
00146     else {
00147         return -1;
00148     }
00149 }
00150 
00151 void process()
00152 {
00153     while(1) {
00154         for (int i = 0; i < SWARM_SIZE; i++) {
00155             int r_id = i;
00156             Position self = get_pos(i);
00157             Position nei;
00158             std::vector<int> neis;
00159             std::map<int, Position>::iterator it;
00160             for (it = pos_map.begin(); it != pos_map.end(); it++) {
00161                 if (it->first == r_id) {
00162                     continue;
00163                 } else {
00164                     nei = it->second;
00165                     if (pos_dis(self, nei) < COM_DIS) {
00166                         neis.push_back(it->first);
00167                     }
00168                 }
00169             }
00170 
00171             std::map < int, std::vector < int > > ::iterator nei_it;
00172             nei_it = neighbor_map.find(r_id);
00173             if (nei_it != neighbor_map.end()) {
00174                 nei_it->second = neis;
00175             } else {
00176                 neighbor_map.insert(std::pair < int, std::vector < int > > (r_id, neis));
00177             }
00178         }
00179         ros::Duration(0.1).sleep();
00180     }
00181 }
00182 
00183 int main(int argc, char** argv)
00184 {
00185     ros::init(argc, argv, "app1_statistic");
00186     ros::NodeHandle nh;
00187 
00188     std::vector<ros::Subscriber> sub_vec;
00189     sub_vec.resize(SWARM_SIZE);
00190 
00191     for(int i = 0; i < SWARM_SIZE; i++) {
00192         stringstream ss;
00193         ss<<"/robot_"<<i<<"/base_pose_ground_truth";
00194         sub_vec[i] = nh.subscribe<nav_msgs::Odometry>(ss.str(), 1000, boost::bind(callback, _1, i));
00195     }
00196 
00197     ros::Duration(1).sleep();
00198 
00199     boost::thread* process_thread_ = new boost::thread(process);
00200 
00201     ofstream file;
00202     file.open("app1_statistic.txt");
00203 
00204     int step = 0;
00205     while(ros::ok()) {
00206         float err = cal_error();
00207         std::cout<<step<<" "<<err<<std::endl;
00208         file<<step<<" "<<err<<std::endl;
00209         step++;
00210         ros::spinOnce();
00211         ros::Duration(0.5).sleep();
00212     }
00213 
00214     ros::spin();
00215     return 0;
00216 }


test_statistic
Author(s):
autogenerated on Thu Jun 6 2019 18:52:37