accelerometer_network_calibration.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2 Software License Agreement (BSD License)
3 
4 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5 All rights reserved.
6 
7 Redistribution and use in source and binary forms, with or without modification, are permitted
8 provided that the following conditions are met:
9 
10 *Redistributions of source code must retain the above copyright notice, this list of
11 conditions and the following disclaimer.
12 *Redistributions in binary form must reproduce the above copyright notice, this list of
13 conditions and the following disclaimer in the documentation and/or other materials provided
14 with the distribution.
15 *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16 endorse or promote products derived from this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 
34 #include <ros/ros.h>
35 #include "std_msgs/String.h"
36 #include <sstream>
37 #include <string>
38 #include <iostream>
39 #include <vector>
40 //Include the message topic
41 #include <imu_network/raw_imu_message.h>
42 #include <imu_network/sensors_values.h>
43 #include <imu_network/sensors_network.h>
44 
45 //INCLUDE SERIAL LIB FROM LAR3/utils
46 #include <serialcom/SerialCom.h>
47 #include <algorithm>
48 
49 using namespace std;
50 
51 vector<float> accel_max[3];
52 vector<float> accel_min[3];
53 
58 int main (int argc ,char** argv)
59 {
60 
61  serialcom::SerialCom serial;
62 
63  ros::init(argc , argv , "accel_network_calibration");
64  ros::NodeHandle n;
65 
66  ros::Rate loop_rate(10);
67 
68  try
69  {
70  string number_buffer;
71  string buffer_aux;
72  string Ax,Ay,Az,Mx,My,Mz,Gx,Gy,Gz;
73  string junk;
74  int number,total_number;
75  int numbered=0;
76  string converter;
77 
78  serial.open("/dev/ttyACM0",115200);
79 
80  usleep(10000000);
81 
82  while (numbered == 0)
83  {
84  serial.write("#n");
85  serial.readLine(&number_buffer,100);
86  if ((count(number_buffer.begin(),number_buffer.end(),'N')) && (count(number_buffer.begin(),number_buffer.end(),',')) && (number_buffer.length()==3))
87  {
88 
89  istringstream ssN(number_buffer);
90  getline(ssN,junk,'N');
91  getline(ssN,converter, ',');
92  total_number = (int) atoi(converter.c_str());
93  ROS_INFO("Comunicação iniciada com %d sensores",total_number);
94  numbered = 1;
95  }
96 
97  }
98  // init the accel_max/min variables
99  for(int i=0;i<total_number;i++)
100  {
101  accel_max[0].push_back(0);
102  accel_min[0].push_back(0);
103  accel_max[1].push_back(0);
104  accel_min[1].push_back(0);
105  accel_max[2].push_back(0);
106  accel_min[2].push_back(0);
107  }
108 
109  // reading and sort the variables of raw imu data & sending it within the message
110  while(ros::ok())
111  {
112 
113  string data[total_number];
114  int ncsa[total_number];
115  int ncsm[total_number];
116  int ncsg[total_number];
117  int na[total_number];
118  int nm[total_number];
119  int ng[total_number];
120 
121  string num[total_number];
122 
123  serial.flush();
124  // ask for IMU data
125  serial.write("#f");
126 
127 
128 
129  for (int c = 0; c<total_number;c++)
130  {
131  try
132  {
133  serial.readLine(&data[c],100);
134 
135  }catch(serialcom::Exception ex)
136 
137  {
138  cout<<ex.what()<<endl;
139  }
140 
141  ncsa[c]=count(data[c].begin(), data[c].end(), ',');
142 
143  na[c]=count(data[c].begin(), data[c].end(), 'A');
144  nm[c]=count(data[c].begin(), data[c].end(), 'M');
145  ng[c]=count(data[c].begin(), data[c].end(), 'G');
146 
147  // testing the content inside buffer
148  if(ncsa[c]!=10)
149  {
150  exit(0);
151  }
152  else
153  {
154 
155  }
156  // verify the sensor number to match with the for cicle
157  istringstream ss(data[c]);
158  getline(ss,junk,'A');
159  num[c] = junk[1];
160  if(c == (int)atoi(num[c].c_str()))
161  {
162  // getting the raw imu data from buffer
163  getline(ss,Ax, ',');
164  getline(ss,Ay, ',');
165  getline(ss,Az, ',');
166  getline(ss,junk,'M');
167  getline(ss,Mx, ',');
168  getline(ss,My, ',');
169  getline(ss,Mz, ',');
170  getline(ss,junk,'G');
171  getline(ss,Gx, ',');
172  getline(ss,Gy, ',');
173  getline(ss,Gz, ',');
174 
175  }
176 
177  if (((double) atof(Ax.c_str())) > accel_max[0][c]) accel_max[0][c] = (double) atof(Ax.c_str());
178  if (((double) atof(Ay.c_str())) > accel_max[1][c]) accel_max[1][c] = (double) atof(Ay.c_str());
179  if (((double) atof(Az.c_str())) > accel_max[2][c]) accel_max[2][c] = (double) atof(Az.c_str());
180 
181  if (((double) atof(Ax.c_str())) < accel_min[0][c]) accel_min[0][c] = (double) atof(Ax.c_str());
182  if (((double) atof(Ay.c_str())) < accel_min[1][c]) accel_min[1][c] = (double) atof(Ay.c_str());
183  if (((double) atof(Az.c_str())) < accel_min[2][c]) accel_min[2][c] = (double) atof(Az.c_str());
184 
185 
186  cout<<"Sensor "<<c<<" -->> AxMAX="<<accel_max[0][c]<<" AyMAX="<<accel_max[1][c]<<" AzMAX="<<accel_max[2][c]<<endl;
187  cout<<"Sensor "<<c<<" -->> AxMIN="<<accel_min[0][c]<<" AyMIN="<<accel_min[1][c]<<" AzMIN="<<accel_min[2][c]<<endl;
188 
189  // storing the raw imu data into the message variables for total_number sensors
190 // values.sensors_val[c].S_Ax= (double) atof(Ax.c_str());
191 // values.sensors_val[c].S_Ay = (double) atof(Ay.c_str());
192 // values.sensors_val[c].S_Az = (double) atof(Az.c_str());
193 //
194 // values.sensors_val[c].S_Mx = (double) atof(Mx.c_str());
195 // values.sensors_val[c].S_My = (double) atof(My.c_str());
196 // values.sensors_val[c].S_Mz = (double) atof(Mz.c_str());
197 //
198 // values.sensors_val[c].S_Gx =(double)atof(Gx.c_str());
199 // values.sensors_val[c].S_Gy =(double)atof(Gy.c_str());
200 // values.sensors_val[c].S_Gz =(double)atof(Gz.c_str());
201 //
202 // values.sensors_val[c].total_number = total_number;
203 // values.sensors_val[c].header.stamp = ros::Time::now();
204 // values.sensors_val[c].number = (int)atoi(num[c].c_str());
205 // values.sensors_val[c].header.frame_id = "imu_raw";
206 
207  }
208 // chatter_pub.publish(values);
209  loop_rate.sleep();
210  }
211  //close COM after CTRL+C intercepted
212  serial.close();
213 // for (int fin = 0 ; fin<total_number ;fin++)
214 // {
215 // cout<<endl<<"RESULTADOS FINAIS..."<<endl;
216 // cout<<"Sensor "<<fin<<" -->> AxMAX="<<accel_max[0][fin]<<" AyMAX="<<accel_max[1][fin]<<" AzMAX="<<accel_max[2][fin]<<endl;
217 // cout
218 // cout<<"Sensor "<<fin<<" -->> AxMIN="<<accel_min[0][fin]<<" AyMIN="<<accel_min[1][fin]<<" AzMIN="<<accel_min[2][fin]<<endl;
219 // }
220 
221  }catch (std::exception& e)
222  {
223  std::cerr << "Exception: " << e.what() << "\n";
224  }
225 
226  return 0;
227 
228 }
int main(int argc, char **argv)
vector< float > accel_min[3]
vector< float > accel_max[3]
ros::NodeHandle * n


imu_network
Author(s): Telmo Rafeiro
autogenerated on Mon Mar 2 2015 01:31:44