Go to the documentation of this file.00001
00021 #include "PingThread.h"
00022 #include "cvd/thread.h"
00023 #include "ros/ros.h"
00024 #include <iostream>
00025 #include <stdio.h>
00026 #include "RosThread.h"
00027 #include "tum_ardrone_gui.h"
00028
00029 PingThread::PingThread()
00030 {
00031 line1[0] = '\0';
00032 line2[0] = '\0';
00033 keepRunning = true;
00034 measure = true;
00035
00036 p500 = 25;
00037 p20000 = 50;
00038
00039 rosThread = NULL;
00040 gui = NULL;
00041 }
00042
00043 PingThread::~PingThread(void)
00044 {
00045
00046
00047 }
00048
00049 void PingThread::startSystem()
00050 {
00051 keepRunning = true;
00052 start();
00053 }
00054
00055 void PingThread::stopSystem()
00056 {
00057 keepRunning = false;
00058 join();
00059 }
00060
00061 double parsePingResult(std::string s)
00062 {
00063
00064 int pos = s.find("time=");
00065 int found = 0;
00066 float ms;
00067 if(pos != std::string::npos)
00068 found = sscanf(s.substr(pos).c_str(),"time=%f",&ms);
00069
00070 if(found == 1 && pos != std::string::npos)
00071 return ms;
00072 else
00073 return 10000;
00074 }
00075
00076 void PingThread::run()
00077 {
00078 std::cout << "Starting PING Thread" << std::endl;
00079
00080 sprintf(pingCommand20000,"ping -c 1 -s 20000 -w 1 192.168.1.1");
00081 sprintf(pingCommand500,"ping -c 1 -s 500 -w 1 192.168.1.1");
00082 ros::Rate r(2.0);
00083 FILE *p;
00084
00085 while(keepRunning)
00086 {
00087 if(measure)
00088 {
00089
00090 p = popen(pingCommand500,"r");
00091 fgets(line1, 200, p);
00092 fgets(line1, 200, p);
00093 pclose(p);
00094
00095
00096 r.sleep();
00097 if(!keepRunning) break;
00098 r.sleep();
00099 if(!keepRunning) break;
00100
00101
00102
00103 p = popen(pingCommand20000,"r");
00104 fgets(line2, 200, p);
00105 fgets(line2, 200, p);
00106 pclose(p);
00107
00108
00109
00110 double res500 = parsePingResult(line1);
00111 double res20000 = parsePingResult(line2);
00112
00113 std::cout << "new ping values: 500->" << res500 << " 20000->" << res20000 << std::endl;
00114
00115
00116 res500 = std::min(1000.0,std::max(10.0,res500));
00117 res20000 = std::min(1000.0,std::max(10.0,res20000));
00118
00119
00120 p500 = 0.7 * p500 + 0.3 * res500;
00121 p20000 = 0.7 * p20000 + 0.3 * res20000;
00122
00123
00124 snprintf(line1,200,"pings %d %d", (int)p500, (int)p20000);
00125 if(rosThread != NULL) rosThread->publishCommand(line1);
00126 if(gui != NULL) gui->setPings((int)p500, (int)p20000);
00127
00128
00129 r.sleep();
00130 if(!keepRunning) break;
00131 r.sleep();
00132 if(!keepRunning) break;
00133 }
00134 else
00135 {
00136 r.sleep();
00137 if(!keepRunning) break;
00138 r.sleep();
00139 if(!keepRunning) break;
00140 r.sleep();
00141 if(!keepRunning) break;
00142 r.sleep();
00143 if(!keepRunning) break;
00144
00145
00146 snprintf(line1,200,"pings %d %d", (int)p500Default, (int)p20000Default);
00147 if(rosThread != NULL) rosThread->publishCommand(line1);
00148 if(gui != NULL) gui->setPings((int)p500Default, (int)p20000Default);
00149 }
00150 }
00151
00152 std::cout << "Exiting PING Thread" << std::endl;
00153 }