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
00033 #include <ros/ros.h>
00034 #include "std_msgs/String.h"
00035 #include <sstream>
00036 #include <string>
00037
00038
00039 #include <imu_network/raw_imu_message.h>
00040 #include <imu_network/sensors_values.h>
00041 #include <imu_network/sensors_network.h>
00042
00043
00044 #include <serialcom/SerialCom.h>
00045 #include <algorithm>
00046
00047 using namespace std;
00048
00053 int main (int argc ,char** argv)
00054 {
00055
00056 serialcom::SerialCom serial;
00057
00058 ros::init(argc , argv , "sensors_raw_data");
00059 ros::NodeHandle n;
00060 ros::Publisher chatter_pub;
00061 chatter_pub = n.advertise<imu_network::sensors_network>("topic_raw_data", 1000);
00062
00063 ros::Rate loop_rate(10);
00064
00065 try
00066 {
00067
00068 string number_buffer;
00069 string buffer_aux;
00070 string Ax,Ay,Az,Mx,My,Mz,Gx,Gy,Gz;
00071 string junk;
00072 int number,total_number;
00073 int numbered=0;
00074 string converter;
00075
00076 serial.open("/dev/ttyACM0",115200);
00077
00078 usleep(10000000);
00079
00080 imu_network::sensors_network values;
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 imu_network::sensors_values sensor;
00102 values.sensors_val.push_back(sensor);
00103 }
00104
00105
00106 while(ros::ok())
00107 {
00108
00109 string data[total_number];
00110 int ncsa[total_number];
00111 int ncsm[total_number];
00112 int ncsg[total_number];
00113 int na[total_number];
00114 int nm[total_number];
00115 int ng[total_number];
00116
00117 string num[total_number];
00118
00119 serial.flush();
00120 serial.write("#f");
00121
00122
00123
00124 for (int c = 0; c<total_number;c++)
00125 {
00126 try
00127 {
00128 serial.readLine(&data[c],100);
00129
00130 }catch(serialcom::Exception ex)
00131
00132 {
00133 cout<<ex.what()<<endl;
00134 }
00135
00136 ncsa[c]=count(data[c].begin(), data[c].end(), ',');
00137
00138 na[c]=count(data[c].begin(), data[c].end(), 'A');
00139 nm[c]=count(data[c].begin(), data[c].end(), 'M');
00140 ng[c]=count(data[c].begin(), data[c].end(), 'G');
00141
00142
00143 if(ncsa[c]!=10)
00144 {
00145 exit(0);
00146 }
00147 else
00148 {
00149
00150 }
00151
00152 istringstream ss(data[c]);
00153 getline(ss,junk,'A');
00154 num[c] = junk[1];
00155 if(c == (int)atoi(num[c].c_str()))
00156 {
00157
00158 getline(ss,Ax, ',');
00159 getline(ss,Ay, ',');
00160 getline(ss,Az, ',');
00161 getline(ss,junk,'M');
00162 getline(ss,Mx, ',');
00163 getline(ss,My, ',');
00164 getline(ss,Mz, ',');
00165 getline(ss,junk,'G');
00166 getline(ss,Gx, ',');
00167 getline(ss,Gy, ',');
00168 getline(ss,Gz, ',');
00169
00170 }
00171
00172 values.sensors_val[c].S_Ax= (double) atof(Ax.c_str());
00173 values.sensors_val[c].S_Ay = (double) atof(Ay.c_str());
00174 values.sensors_val[c].S_Az = (double) atof(Az.c_str());
00175
00176 values.sensors_val[c].S_Mx = (double) atof(Mx.c_str());
00177 values.sensors_val[c].S_My = (double) atof(My.c_str());
00178 values.sensors_val[c].S_Mz = (double) atof(Mz.c_str());
00179
00180 values.sensors_val[c].S_Gx =(double)atof(Gx.c_str());
00181 values.sensors_val[c].S_Gy =(double)atof(Gy.c_str());
00182 values.sensors_val[c].S_Gz =(double)atof(Gz.c_str());
00183
00184 values.sensors_val[c].total_number = total_number;
00185 values.sensors_val[c].header.stamp = ros::Time::now();
00186 values.sensors_val[c].number = (int)atoi(num[c].c_str());
00187 values.sensors_val[c].header.frame_id = "imu_raw";
00188
00189 }
00190 chatter_pub.publish(values);
00191 loop_rate.sleep();
00192 }
00193
00194 serial.close();
00195
00196 }catch (std::exception& e)
00197 {
00198 std::cerr << "Exception: " << e.what() << "\n";
00199 }
00200
00201 return 0;
00202
00203 }