orientation_preception_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/SerialCom.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 #include <geometry_msgs/Vector3.h>
69 
70 using namespace std;
71 using namespace boost;
72 
79 class Plane
80 {
81 public:
88  {
89  a=0;b=0;c=0;d=0;
90  }
91 
92  double a,b,c,d;
93 };
99 class SharpMath
100 {
101 public:
108  {
109  }
115  void readParameters(string parameters_file)
116  {
117  cv::FileStorage parameters(parameters_file.c_str(),cv::FileStorage::READ);
118 
119  number_sensors = (int)parameters["number_sensors"];
120 
121 // cout << "sensores: " << number_sensors << endl;
122 
123  for(uint s = 0;s<number_sensors;s++)
124  {
125  Eigen::Vector2d pos;
126 
127  pos(0) = parameters["x"+to_string(s)];
128  pos(1) = parameters["y"+to_string(s)];
129 
130  sensors_positions.push_back(pos);
131 
132  Eigen::VectorXd curve(4);
133 
134  curve(0) = parameters["p1_"+to_string(s)];
135  curve(1) = parameters["p2_"+to_string(s)];
136  curve(2) = parameters["p3_"+to_string(s)];
137  curve(3) = parameters["p4_"+to_string(s)];
138 
139  sensors_curve_parameters.push_back(curve);
140  }
141 
142  pitch_bias = parameters["pitch_bias"];
143  roll_bias = parameters["roll_bias"];
144 
145 // cout << "pitch: " << pitch_bias << " roll: " << roll_bias << endl;
146 // cout << "sensor n: " << number_sensors << " x0 " << sensors_positions[0](0) << " y0 " << sensors_positions[0](1) << " x1 " << sensors_positions[1](0) << " y1 " << sensors_positions[1](1) << " x2 " << sensors_positions[2](0) << " y2 " << sensors_positions[2](1) << " x3 " << sensors_positions[3](0) << " y3 " << sensors_positions[3](1) << " x4 " << sensors_positions[4](0) << " y4 " << sensors_positions[4](1) << " x5 " << sensors_positions[5](0) << " y5 " << sensors_positions[5](1) << " x6 " << sensors_positions[6](0) << " y6 " << sensors_positions[6](1) << " x7 " << sensors_positions[7](0) << " y7 " << sensors_positions[7](1) << endl;
147  }
154  Plane getPlane(vector<double> values)
155  {
156 // for(uint n=0;n<number_sensors;n++)
157 // cout << "Valores: " << values[n] << endl;
158 
159  Eigen::VectorXd g(number_sensors);
160  g = Eigen::VectorXd::Ones(number_sensors);
161 
162 // cout<<"g: "<<g<<endl;
163 
164  Eigen::MatrixXd F(number_sensors,3);
165 
166  for(uint i=0;i<number_sensors;i++)
167  {
168  F(i,0) = sensors_positions[i](0);
169  F(i,1) = sensors_positions[i](1);
170  F(i,2) = values[i];
171  }
172 
173  Eigen::VectorXd r(3);
174 
175  r = ((F.transpose()*F).inverse() * F.transpose())*g;
176 
177  double zp = ((-r(0)/r(2))*sensors_positions[0](0)) - ((r(1)/r(2))*sensors_positions[0](1));
178 
179  double d = values[0] - zp;
180  double a = r(0)*d;
181  double b = r(1)*d;
182  double c = r(2)*d;
183 
184 // cout << "F: " << F << endl;
185 // cout << "r: " << r << endl;
186 
187  Plane temp;
188 
189  temp.a=a;
190  temp.b=b;
191  temp.c=c;
192  temp.d=d;
193 
194  return temp;
195  }
202  double getPitch( Plane p)
203  {
204  double a, b, c, d;
205  a=p.a;
206  b=p.b;
207  c=p.c;
208  d=p.d;
209  return ((180./M_PI)*(atan2(d,(d*c/a)))) - pitch_bias;
210  }
217  double getRoll( Plane p)
218  {
219  double a, b, c, d;
220  a=p.a;
221  b=p.b;
222  c=p.c;
223  d=p.d;
224  return ((180./M_PI)*(atan2(d,(d*c/b)))) - roll_bias;
225  }
226 
227 
228 private:
229 
230  uint number_sensors;
231  vector<Eigen::Vector2d> sensors_positions;
232  vector<Eigen::VectorXd> sensors_curve_parameters;
233 
234  double pitch_bias;
235  double roll_bias;
236 
237 };
238 
245 {
246 public:
251  OptoelectricVehiclePose(const ros::NodeHandle& nh):
252  nh_(nh)
253  {
254  // iniciar mensagens
255  setupMessaging();
256 
257  string parameters_url;
258 
259  nh_.param("parameters",parameters_url,std::string("no parameters file"));
260 
261  cout << "url: " << parameters_url << endl;
262 
263  s.readParameters(parameters_url);
264  // iniciar leitura dos dados yaml
265  }
266  // Inicia os publicadores e os subscrevedores
272  {
274 
275  new_data.resize(8,false);
276 
277  for(uint i=0;i<8;i++)
278  {
279  ros::Subscriber sub = nh_.subscribe<sensor_msgs::Range>("/optoelectic_vehicle_base/sharp_"+to_string(i), 1, boost::bind(&OptoelectricVehiclePose::sharpCallback,this,_1,i));
280 
281  sharp_subscriber.push_back(sub);
282  }
283 
284 
286 
287  pose_publisher = nh_.advertise<geometry_msgs::Vector3>("pose_orientation", 1000);
288  car_mark_pub = nh_.advertise<visualization_msgs::Marker>("atlascar_ori",1000);
289  }
296  void sharpCallback(const sensor_msgs::Range::ConstPtr msg,int i)
297  {
298  //cout<<"Received sensor: "<<i<< " value: "<<msg->range<<endl;
299  if(msg->range<1023)
300  {
301  sharp_values[i]=msg->range;
302  new_data[i] = true;
303  }
304  }
310  void carMarker(geometry_msgs::Vector3 pose)
311  {
312  pose.x=pose.x*3.14/180;
313  pose.y=pose.y*3.14/180;
314  pose.z=pose.z*3.14/180;
315 
316  car_marker.header.frame_id = "base_link";
317 
318  car_marker.id = 8484;
319  car_marker.ns = "atlas";
320 
321  car_marker.type = visualization_msgs::Marker::MESH_RESOURCE;
322  car_marker.action = visualization_msgs::Marker::ADD;
323 
324 
325  car_marker.pose.position.x = 0;
326  car_marker.pose.position.y = 0;
327  car_marker.pose.position.z = 0.4;
328  // Escala do marcador
329  car_marker.scale.x = 1;
330  car_marker.scale.y = 1;
331  car_marker.scale.z = 1;
332 
333  car_marker.pose.orientation.x = sin(pose.x/2)*cos(pose.y/2)*cos(pose.z/2) - cos(pose.x/2)*sin(pose.y/2)*sin(pose.z/2);
334  car_marker.pose.orientation.y = cos(pose.x/2)*sin(pose.y/2)*cos(pose.z/2) + sin(pose.x/2)*cos(pose.y/2)*sin(pose.z/2);
335  car_marker.pose.orientation.z = cos(pose.x/2)*cos(pose.y/2)*sin(pose.z/2) - sin(pose.x/2)*sin(pose.y/2)*cos(pose.z/2);
336  car_marker.pose.orientation.w = cos(pose.x/2)*cos(pose.y/2)*cos(pose.z/2) + sin(pose.x/2)*sin(pose.y/2)*sin(pose.z/2);
337 
338 
339  // Cor do marcador (255,99,71)
340  car_marker.color.r = 0.0f;
341  car_marker.color.g = 0.0f;
342  car_marker.color.b = 0.0f;
343  car_marker.color.a = 0.0f;
344 
345  car_marker.mesh_use_embedded_materials=1;
346 
347  car_marker.mesh_resource = "package://optoelectric/ship/FordEscort_ori.DAE";
348 
349  car_marker.lifetime = ros::Duration();
350  }
351 
356  void loop()
357  {
358  ros::Rate r(100);
359 
360  while(ros::ok())
361  {
362  r.sleep();
363  ros::spinOnce();
364 
365  bool process = true;
366 
367  for(bool v: new_data)
368  {
369  if(v==false)
370  {
371  process = false;
372  break;
373  }
374  }
375 
376  if(process==false)
377  continue;
378 
379  vector<double> values;
380  for(uint i=0;i<8;i++)
381  {
382  double val = sharp_values[i];
383  values.push_back(val);
384 // cout << "i: " << i << " sensor " << val << endl;
385  }
386 
387  Plane plane = s.getPlane(values);
388 
389  pitch = s.getPitch(plane);
390  roll = s.getRoll(plane);
391 
392  if (roll > 90)
393  roll=roll-180;
394  if (roll < -90)
395  roll=roll+180;
396  if (pitch > 90)
397  pitch=pitch-180;
398  if (pitch < -90)
399  pitch=pitch+180;
400 
401  cout << "pitch: " << pitch << " roll: " << roll << endl;
402 
403  geometry_msgs::Vector3 posee;
404 
405  if(pitch < 45 && roll < 45)
406  {
407  posee.x=roll;
408  posee.y=pitch;
409  posee.z=0;
410 
411 
412 
413  pose_publisher.publish(posee);
414 
415  carMarker(posee);
416  car_marker.header.stamp = ros::Time::now();
417  car_mark_pub.publish(car_marker);
418  }
419 
420 
421  new_data.clear();
422  new_data.resize(8,false);
423 
424  }
425  }
426 
427 private:
428 
429  visualization_msgs::Marker car_marker;
430  ros::Publisher car_mark_pub;
431 
432  ros::NodeHandle nh_;
433 
434  double pitch;
435  double roll;
436 
437  SharpMath s;
438 
439  ros::Publisher pose_publisher;
440 
441  vector<ros::Subscriber> sharp_subscriber;
442 
443  int sharp_values[8];
444  vector<bool> new_data;
445 
446 };
447 
452 int main(int argc, char* argv[])
453 {
454  // Iniciar o ros
455  ros::init(argc, argv, "preception_orientation_base");
456  // Handle
457  ros::NodeHandle nh("~");
458 
459  // inciar
460  OptoelectricVehiclePose opto(nh);
461 
462  opto.loop();
463 
464  return 0;
465 }
SharpMath()
Class constructor.
int main(int argc, char *argv[])
main Init ros and stays in loop forever.
OptoelectricVehiclePose(const ros::NodeHandle &nh)
Class constructor Init the serial port, open the txt file and the yaml file.
void carMarker(geometry_msgs::Vector3 pose)
carMarker Function responsible publish the car marker.
void loop()
loop Function responsible to put the program running forever.
SharpMath.
Plane()
Class constructor.
Plane.
void sharpCallback(const sensor_msgs::Range::ConstPtr msg, int i)
sharpCallback Function responsible evaluate is the message is valid.
double getPitch(Plane p)
getPitch Function responsible for calculate the plane pitch.
Plane getPlane(vector< double > values)
getPlane Function responsible for calculate the plane acording to the given points.
visualization_msgs::Marker car_marker
double getRoll(Plane p)
getRoll Function responsible for calculate the plane roll.
OptoelectricVehiclePose.
void readParameters(string parameters_file)
readParameters Function responsible for read the parameters from yaml file.
void setupMessaging()
setupMessaging Function responsible for creat the publishers.


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