orientation_base.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License) *
3 
4  Copyright (c) 2011-2014, 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 
33 #include <iostream>
34 #include <pthread.h>
35 
36 #include <math.h>
37 #include <string>
38 #include <sstream>
39 #include <fstream>
40 #include <stdio.h>
41 #include <stdlib.h>
42 #include <signal.h>
43 #include <iostream>
44 
45 #include <boost/asio.hpp>
46 #include <boost/array.hpp>
47 #include <boost/thread.hpp>
48 #include <boost/asio/ip/tcp.hpp>
49 #include <boost/thread/mutex.hpp>
50 #include <boost/thread/locks.hpp>
51 #include <boost/thread/thread.hpp>
52 
53 #include <ros/ros.h>
54 
55 #include <visualization_msgs/Marker.h>
56 #include <visualization_msgs/MarkerArray.h>
57 
58 #include <Eigen/Dense>
59 #include <Eigen/Geometry>
60 
61 #include <serialcom/BufferedAsyncSerial.h>
62 
63 #include <opencv2/core/core.hpp>
64 #include <opencv2/highgui/highgui.hpp>
65 
66 #include <sensor_msgs/Range.h>
67 #include <ros/package.h>
68 
69 using namespace std;
70 using namespace boost;
77 // Class to defini the plane coeficients
78 class Plane
79 {
80 
81 public:
88  {
89  a=0;b=0;c=0;d=0;
90  }
91 
92  double a,b,c,d;
93 };
94 
101 {
102 public:
109  {
110 
111  }
112 
118  void readParameters(string parameters_file)
119  {
120  cv::FileStorage parameters(parameters_file.c_str(),cv::FileStorage::READ);
121 
122  number_sensors = (int)parameters["number_sensors"];
123 
124  cout<<"number_sensors: "<<number_sensors<<endl;
125  for(uint s = 0;s<number_sensors;s++)
126  {
127  Eigen::Vector2d pos;
128 
129  pos(0) = parameters["x"+to_string(s)];
130  pos(1) = parameters["y"+to_string(s)];
131 
132  sensors_positions.push_back(pos);
133 
134  Eigen::VectorXd curve(4);
135 
136  curve(0) = parameters["p1_"+to_string(s)];
137  curve(1) = parameters["p2_"+to_string(s)];
138  curve(2) = parameters["p3_"+to_string(s)];
139  curve(3) = parameters["p4_"+to_string(s)];
140 
141  sensors_curve_parameters.push_back(curve);
142  }
143  cout<<"Reed parameters: "<<sensors_curve_parameters.size()<<endl;
144  pitch_bias = parameters["pitch_bias"];
145  roll_bias = parameters["roll_bias"];
146  }
147 
154  double convertoV(double A)
155  {
156  return A*5/1023;
157  }
158 
166  double curveCalibration(uint sensor_id, double value)
167  {
168  Eigen::VectorXd curve_parameters = sensors_curve_parameters[sensor_id];
169  double a = curve_parameters(0);
170  double b = curve_parameters(1);
171  double c = curve_parameters(2);
172  double d = curve_parameters(3);
173 
174 // cout << "a: " << a << "b: " << b << "c: " << c << "d: " << d << "valor: " << a*exp(b*value)+c*exp(d*value) << endl;
175 
176  return a*exp(b*value)+c*exp(d*value);
177  }
178 
179 // Plane getPlane(vector<double> values)
180 // {
181 // Eigen::VectorXd g(values.size());
182 // g = Eigen::VectorXd::Ones(values.size());
183 //
184 // cout<<"g: "<<g<<endl;
185 //
186 // Eigen::MatrixXd F(values.size(),3);
187 //
188 // for(uint i=0;i<values.size();i++)
189 // {
190 // F(i,0) = sensors_positions[i](0);
191 // F(i,1) = sensors_positions[i](1);
192 // F(i,2) = values[i];
193 // }
194 //
195 // Eigen::VectorXd r(3);
196 //
197 // r = ((F.transpose()*F).inverse() * F.transpose())*g;
198 //
199 // double zp = ((-r(0)/r(2))*sensors_positions[0](0)) - ((r(1)/r(2))*sensors_positions[0](1));
200 //
201 // double d = values[0] - zp;
202 // double a = r(0)*d;
203 // double b = r(1)*d;
204 // double c = r(2)*d;
205 //
206 // Plane temp;
207 //
208 // temp.a=a;
209 // temp.b=b;
210 // temp.c=c;
211 // temp.d=d;
212 //
213 // return temp;
214 // }
215 
216 // double getPitch( Plane p)
217 // {
218 // double a, b, c, d;
219 // a=p.a;
220 // b=p.b;
221 // c=p.c;
222 // d=p.d;
223 // return ((180./M_PI)*(atan2(d,(d*c/a)))) - pitch_bias;
224 // }
225 // double getRoll( Plane p)
226 // {
227 // double a, b, c, d;
228 // a=p.a;
229 // b=p.b;
230 // c=p.c;
231 // d=p.d;
232 // return ((180./M_PI)*(atan2(d,(d*c/b)))) - roll_bias;
233 // }
234 
235 
236 private:
237 
239  vector<Eigen::Vector2d> sensors_positions;
240  vector<Eigen::VectorXd> sensors_curve_parameters;
241 
242  double pitch_bias;
243  double roll_bias;
244 
245 };
253 {
254 public:
259  OptoelectricVehiclePose(const ros::NodeHandle& nh):
260  nh_(nh),
261  serial("/dev/ttyACM0",115200)
262  {
263 
264  outfile1.open(("/home/carpinteiro/workingcopies/lar4/src/sensors/optoelectric/data/Sensors_bag.txt"));
265  // iniciar mensagens
266  setupMessaging();
267 
268  string parameters_url;
269 
270  nh_.param("parameters",parameters_url,std::string("no parameters file"));
271 
272  string package_tag = "package://";
273  int pos = parameters_url.find(package_tag);
274  if(pos != string::npos)
275  {
276  //String contains package, replace by package path
277  int fpos = parameters_url.find("/",pos+package_tag.length());
278  string package = parameters_url.substr(pos+package_tag.length(),fpos-(pos+package_tag.length()));
279 
280  string package_path = ros::package::getPath(package);
281  parameters_url.replace(pos,fpos-pos,package_path);
282  }
283 
284  cout << "url: " << parameters_url << endl;
285 
286  s.readParameters(parameters_url);
287  // iniciar leitura dos dados yaml
288  }
289  // Inicia os publicadores e os subscrevedores
295  {
297 
299  // advertive da ship_move_requests para posição desejada
300  for(uint i=0;i<8;i++)
301  {
302  ros::Publisher pub = nh_.advertise<sensor_msgs::Range>("sharp_"+to_string(i), 1000);
303  publishers.push_back(pub);
304  }
305  }
306  // Inicia a leitura do serial port
307 
314  bool checkMessageIntegrety(string msg)
315  {
316  bool is_valid = true;
317 
318  if(msg.length()==0)
319  return false;
320 
321  if(msg.find("A0 ")==string::npos)
322  is_valid = false;
323 
324  if(msg.find("A1 ")==string::npos)
325  is_valid = false;
326 
327  if(msg.find("A2 ")==string::npos)
328  is_valid = false;
329 
330  if(msg.find("A3 ")==string::npos)
331  is_valid = false;
332 
333  if(msg.find("A4 ")==string::npos)
334  is_valid = false;
335 
336  if(msg.find("A5 ")==string::npos)
337  is_valid = false;
338 
339  if(msg.find("A6 ")==string::npos)
340  is_valid = false;
341 
342  if(msg.find("A7 ")==string::npos)
343  is_valid = false;
344 
345  return is_valid;
346  }
351  void loop()
352  {
353  ros::Rate r(100);
354 
355  while(ros::ok())
356  {
357  ros::spinOnce();
358  r.sleep();
359 
360  string line = serial.readStringUntil("\n");
361 
362  if(checkMessageIntegrety(line)==false)
363  {
364 // cout<<"Error: Invalid message ("<<line.length()<<"): "<<line<<endl;
365  continue;
366  }
367 
368  cout<<endl;
369  cout<<"line: "<<endl;
370  cout<<line<<endl;
371  cout<<"size: "<<line.length()<<endl;
372 
373  int readings[8];
374  int values_reed = sscanf(line.c_str(),"%*s %d %*s %d %*s %d %*s %d %*s %d %*s %d %*s %d %*s %d",&readings[0],&readings[1],&readings[2],&readings[3],&readings[4],&readings[5],&readings[6],&readings[7]);
375 
376  cout << "leituras: " << readings[0] << " " <<readings[1] << " " <<readings[2] << " " <<readings[3] << " " <<readings[4] << " " <<readings[5] << " " <<readings[6] << " " <<readings[7] << " " << endl;
377 
378  if(values_reed != 8)
379  {
380  cout<<"Failed to read all 8 values"<<endl;
381  cout<<"Read: "<<values_reed<<endl;
382  perror("Error");
383  }
384 
385  vector<double> values;
386  for(int i=0;i<values_reed;i++)
387  {
388  double voltage = s.convertoV(readings[i]);
389  double value = s.curveCalibration(i,voltage);
390  values.push_back(value);
391  }
392  // Publicar sensores
393 
394  for(uint i=0;i<values.size();i++)
395  {
396  sensor_msgs::Range msg;
397  msg.range=values[i];
398  msg.header.stamp = ros::Time::now();
399  msg.header.frame_id = "sharp_"+to_string(i);
400  cout << "msg: " << msg.range << endl;
401  publishers[i].publish(msg);
402  }
403 
404  outfile1<<ros::Time::now()<<" ";
405 
406  for(uint i=0;i<8;i++)
407  {
408  if(i<values.size())
409  outfile1<<" "<<values[i];
410  else
411  outfile1<<" NaN";
412 
413  }
414 
415  outfile1<<"\n";
416 
417 // Plane plane = s.getPlane(values);
418 //
419 // double pitch = s.getPitch(plane);
420 // double roll = s.getRoll(plane);
421 
422 
423  }
424 
425  }
426 
427 private:
428 
429  ros::NodeHandle nh_;
430 
431  double pitch;
432  double roll;
433 
434  ofstream outfile1;
435 
437  BufferedAsyncSerial serial;
438 
439  vector<ros::Publisher> publishers;
440 
441 };
442 
447 int main(int argc, char* argv[])
448 {
449  // Iniciar o ros
450  ros::init(argc, argv, "orientation_base");
451  // Handle
452  ros::NodeHandle nh("~");
453 
454  // inciar
455  OptoelectricVehiclePose opto(nh);
456 
457  opto.loop();
458 
459  return 0;
460 }
SharpMath()
Class constructor.
OptoelectricVehiclePose(const ros::NodeHandle &nh)
Class constructor Init the serial port, open the txt file and the yaml file.
vector< Eigen::Vector2d > sensors_positions
void loop()
loop Function responsible to put the program running forever.
vector< Eigen::VectorXd > sensors_curve_parameters
SharpMath.
double curveCalibration(uint sensor_id, double value)
curveCalibration Function responsible for convert the voltage signal to distance. Diferent sensors ha...
double convertoV(double A)
convertoV Function responsible for convert the analog signal to the equivalent voltage.
Plane()
Class constructor.
Plane.
int main(int argc, char *argv[])
main Init ros and stays in loop forever.
vector< ros::Publisher > publishers
OptoelectricVehiclePose.
void readParameters(string parameters_file)
readParameters Function responsible for read the parameters from yaml file.
BufferedAsyncSerial serial
void setupMessaging()
setupMessaging Function responsible for creat the publishers.
bool checkMessageIntegrety(string msg)
checkMessageIntegrety Function responsible evaluate is the message is valid.


optoelectric
Author(s): Pedro Salvado, Gonçalo Carpinteiro
autogenerated on Mon Mar 2 2015 01:32:31