00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00034 #include <ros/ros.h>
00035 #include "std_msgs/String.h"
00036 #include <sstream>
00037 #include <string>
00038 #include <iostream>
00039 #include <vector>
00040
00041 #include <imu_network/raw_imu_message.h>
00042 #include <imu_network/sensors_values.h>
00043 #include <imu_network/sensors_network.h>
00044
00045
00046 #include <serialcom/SerialCom.h>
00047 #include <algorithm>
00048
00049 using namespace std;
00050
00051 vector<float> accel_max[3];
00052 vector<float> accel_min[3];
00053
00058 int main (int argc ,char** argv)
00059 {
00060
00061 serialcom::SerialCom serial;
00062
00063 ros::init(argc , argv , "accel_network_calibration");
00064 ros::NodeHandle n;
00065
00066 ros::Rate loop_rate(10);
00067
00068 try
00069 {
00070 string number_buffer;
00071 string buffer_aux;
00072 string Ax,Ay,Az,Mx,My,Mz,Gx,Gy,Gz;
00073 string junk;
00074 int number,total_number;
00075 int numbered=0;
00076 string converter;
00077
00078 serial.open("/dev/ttyACM0",115200);
00079
00080 usleep(10000000);
00081
00082 while (numbered == 0)
00083 {
00084 serial.write("#n");
00085 serial.readLine(&number_buffer,100);
00086 if ((count(number_buffer.begin(),number_buffer.end(),'N')) && (count(number_buffer.begin(),number_buffer.end(),',')) && (number_buffer.length()==3))
00087 {
00088
00089 istringstream ssN(number_buffer);
00090 getline(ssN,junk,'N');
00091 getline(ssN,converter, ',');
00092 total_number = (int) atoi(converter.c_str());
00093 ROS_INFO("Comunicação iniciada com %d sensores",total_number);
00094 numbered = 1;
00095 }
00096
00097 }
00098
00099 for(int i=0;i<total_number;i++)
00100 {
00101 accel_max[0].push_back(0);
00102 accel_min[0].push_back(0);
00103 accel_max[1].push_back(0);
00104 accel_min[1].push_back(0);
00105 accel_max[2].push_back(0);
00106 accel_min[2].push_back(0);
00107 }
00108
00109
00110 while(ros::ok())
00111 {
00112
00113 string data[total_number];
00114 int ncsa[total_number];
00115 int ncsm[total_number];
00116 int ncsg[total_number];
00117 int na[total_number];
00118 int nm[total_number];
00119 int ng[total_number];
00120
00121 string num[total_number];
00122
00123 serial.flush();
00124
00125 serial.write("#f");
00126
00127
00128
00129 for (int c = 0; c<total_number;c++)
00130 {
00131 try
00132 {
00133 serial.readLine(&data[c],100);
00134
00135 }catch(serialcom::Exception ex)
00136
00137 {
00138 cout<<ex.what()<<endl;
00139 }
00140
00141 ncsa[c]=count(data[c].begin(), data[c].end(), ',');
00142
00143 na[c]=count(data[c].begin(), data[c].end(), 'A');
00144 nm[c]=count(data[c].begin(), data[c].end(), 'M');
00145 ng[c]=count(data[c].begin(), data[c].end(), 'G');
00146
00147
00148 if(ncsa[c]!=10)
00149 {
00150 exit(0);
00151 }
00152 else
00153 {
00154
00155 }
00156
00157 istringstream ss(data[c]);
00158 getline(ss,junk,'A');
00159 num[c] = junk[1];
00160 if(c == (int)atoi(num[c].c_str()))
00161 {
00162
00163 getline(ss,Ax, ',');
00164 getline(ss,Ay, ',');
00165 getline(ss,Az, ',');
00166 getline(ss,junk,'M');
00167 getline(ss,Mx, ',');
00168 getline(ss,My, ',');
00169 getline(ss,Mz, ',');
00170 getline(ss,junk,'G');
00171 getline(ss,Gx, ',');
00172 getline(ss,Gy, ',');
00173 getline(ss,Gz, ',');
00174
00175 }
00176
00177 if (((double) atof(Ax.c_str())) > accel_max[0][c]) accel_max[0][c] = (double) atof(Ax.c_str());
00178 if (((double) atof(Ay.c_str())) > accel_max[1][c]) accel_max[1][c] = (double) atof(Ay.c_str());
00179 if (((double) atof(Az.c_str())) > accel_max[2][c]) accel_max[2][c] = (double) atof(Az.c_str());
00180
00181 if (((double) atof(Ax.c_str())) < accel_min[0][c]) accel_min[0][c] = (double) atof(Ax.c_str());
00182 if (((double) atof(Ay.c_str())) < accel_min[1][c]) accel_min[1][c] = (double) atof(Ay.c_str());
00183 if (((double) atof(Az.c_str())) < accel_min[2][c]) accel_min[2][c] = (double) atof(Az.c_str());
00184
00185
00186 cout<<"Sensor "<<c<<" -->> AxMAX="<<accel_max[0][c]<<" AyMAX="<<accel_max[1][c]<<" AzMAX="<<accel_max[2][c]<<endl;
00187 cout<<"Sensor "<<c<<" -->> AxMIN="<<accel_min[0][c]<<" AyMIN="<<accel_min[1][c]<<" AzMIN="<<accel_min[2][c]<<endl;
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207 }
00208
00209 loop_rate.sleep();
00210 }
00211
00212 serial.close();
00213
00214
00215
00216
00217
00218
00219
00220
00221 }catch (std::exception& e)
00222 {
00223 std::cerr << "Exception: " << e.what() << "\n";
00224 }
00225
00226 return 0;
00227
00228 }