sensors_receiver.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 ***************************************************************************************************/
33 #include <ros/ros.h>
34 #include "std_msgs/String.h"
35 #include <sstream>
36 #include <string>
37 
38 //Include of message topic
39 #include <imu_network/raw_imu_message.h>
40 #include <imu_network/sensors_values.h>
41 #include <imu_network/sensors_network.h>
42 
43 //INCLUDE SERIAL LIB FROM LAR3/utils
44 #include <serialcom/SerialCom.h>
45 #include <algorithm>
46 
47 using namespace std;
48 
53 int main (int argc ,char** argv)
54 {
55 
56  serialcom::SerialCom serial;
57 
58  ros::init(argc , argv , "sensors_raw_data");
59  ros::NodeHandle n;
60  ros::Publisher chatter_pub;
61  chatter_pub = n.advertise<imu_network::sensors_network>("topic_raw_data", 1000);
62 
63  ros::Rate loop_rate(10);
64 
65  try
66  {
67 
68  string number_buffer;
69  string buffer_aux;
70  string Ax,Ay,Az,Mx,My,Mz,Gx,Gy,Gz;
71  string junk;
72  int number,total_number;
73  int numbered=0;
74  string converter;
75 
76  serial.open("/dev/ttyACM0",115200);
77 
78  usleep(10000000);
79 
80  imu_network::sensors_network values;
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 of message variable for total_number sensors
99  for(int i=0;i<total_number;i++)
100  {
101  imu_network::sensors_values sensor;
102  values.sensors_val.push_back(sensor);
103  }
104 
105 // reading and sort the variables of raw imu data & sending it within the message
106  while(ros::ok())
107  {
108 
109  string data[total_number];
110  int ncsa[total_number];
111  int ncsm[total_number];
112  int ncsg[total_number];
113  int na[total_number];
114  int nm[total_number];
115  int ng[total_number];
116 
117  string num[total_number];
118 
119  serial.flush();
120  serial.write("#f");
121 
122 
123 
124  for (int c = 0; c<total_number;c++)
125  {
126  try
127  {
128  serial.readLine(&data[c],100);
129 
130  }catch(serialcom::Exception ex)
131 
132  {
133  cout<<ex.what()<<endl;
134  }
135 
136  ncsa[c]=count(data[c].begin(), data[c].end(), ',');
137 
138  na[c]=count(data[c].begin(), data[c].end(), 'A');
139  nm[c]=count(data[c].begin(), data[c].end(), 'M');
140  ng[c]=count(data[c].begin(), data[c].end(), 'G');
141 
142  // testing the content inside buffer
143  if(ncsa[c]!=10)
144  {
145  exit(0);
146  }
147  else
148  {
149 
150  }
151 // verify the sensor number to match with the for cicle
152  istringstream ss(data[c]);
153  getline(ss,junk,'A');
154  num[c] = junk[1];
155  if(c == (int)atoi(num[c].c_str()))
156  {
157 // getting the raw imu data from buffer
158  getline(ss,Ax, ',');
159  getline(ss,Ay, ',');
160  getline(ss,Az, ',');
161  getline(ss,junk,'M');
162  getline(ss,Mx, ',');
163  getline(ss,My, ',');
164  getline(ss,Mz, ',');
165  getline(ss,junk,'G');
166  getline(ss,Gx, ',');
167  getline(ss,Gy, ',');
168  getline(ss,Gz, ',');
169 
170  }
171 // storing the raw imu data into the message variables for total_number sensors
172  values.sensors_val[c].S_Ax= (double) atof(Ax.c_str());
173  values.sensors_val[c].S_Ay = (double) atof(Ay.c_str());
174  values.sensors_val[c].S_Az = (double) atof(Az.c_str());
175 
176  values.sensors_val[c].S_Mx = (double) atof(Mx.c_str());
177  values.sensors_val[c].S_My = (double) atof(My.c_str());
178  values.sensors_val[c].S_Mz = (double) atof(Mz.c_str());
179 
180  values.sensors_val[c].S_Gx =(double)atof(Gx.c_str());
181  values.sensors_val[c].S_Gy =(double)atof(Gy.c_str());
182  values.sensors_val[c].S_Gz =(double)atof(Gz.c_str());
183 
184  values.sensors_val[c].total_number = total_number;
185  values.sensors_val[c].header.stamp = ros::Time::now();
186  values.sensors_val[c].number = (int)atoi(num[c].c_str());
187  values.sensors_val[c].header.frame_id = "imu_raw";
188 
189  }
190  chatter_pub.publish(values);
191  loop_rate.sleep();
192  }
193 //close COM after CTRL+C intercepted
194  serial.close();
195 
196  }catch (std::exception& e)
197  {
198  std::cerr << "Exception: " << e.what() << "\n";
199  }
200 
201  return 0;
202 
203 }
int main(int argc, char **argv)
ros::Publisher chatter_pub
ros::NodeHandle * n


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