car_attitude2ground.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 optoelectric::sensor_sharp_msg sharp_msg;
34 vector<double> measures;
36 
43 void SensorCallback (const optoelectric::sensor_sharp_msg &msg)
44 {
45  //ROS_INFO("sensor_sharp_msg_received");
46  sharp_msg=msg;
47  new_status_message=true;
48 
49 }
54 int main(int argc,char**argv)
55 {
56 
57  ros::init(argc, argv, "sensor_sharp_transformation_node");
58  ros::NodeHandle n;
59  ros::Subscriber sensor_msg_subs= n.subscribe("/snr/opto/sensor",1, SensorCallback);
60  ros::Rate r(60.0);
61 
62  int count_f_l=0;
63  int count_f_r=0;
64  int count_b_l=0;
65  int count_b_r=0;
66  float d_front_left_array[8];
67  float d_front_right_array[8];
68  float d_back_left_array[8];
69  float d_back_right_array[8];
70  while(n.ok())
71  {
72  spinOnce();
73  r.sleep();
75  continue;
76 
77  new_status_message=false;
78 
79 
80  float dist_front_left=Median_Filter(count_f_l,sharp_msg.d_front_left,d_front_left_array);
81  count_f_l++;
82 
83  float dist_front_right=Median_Filter(count_f_r,sharp_msg.d_front_right,d_front_right_array);
84  count_f_r++;
85 
86  float dist_back_left=Median_Filter(count_b_l,sharp_msg.d_back_left,d_back_left_array);
87  count_b_l++;
88 
89  float dist_back_right=Median_Filter(count_b_r,sharp_msg.d_back_right,d_back_right_array);
90  count_b_r++;
91 
92 
93  float z_mean=(dist_front_left + dist_front_right + dist_back_left + dist_back_right)/4;
94  float roll_front=atan2((dist_front_left - dist_front_right),1.27);
95  float roll_back=atan2((dist_back_left - dist_back_right),0.67);
96 
97  float pitch=atan2((dist_back_left + dist_back_right)*0.5 - (dist_front_left + dist_front_right)*0.5,1.39*2);
98  static tf::TransformBroadcaster br;
99  tf::Transform transform;
100  transform.setOrigin( tf::Vector3(0.0, 0.0, z_mean) );
101  transform.setRotation(tf::createQuaternionFromRPY((roll_front+roll_back)*0.5, pitch, 0) );
102  br.sendTransform(tf::StampedTransform(transform, sharp_msg.header.stamp,"/ground", "/atc/vehicle/center_car_axis" ));
103 
104  }
105 
106  return 0;
107 }
108 
int main(int argc, char **argv)
main
float Median_Filter(int countt, float dist, float array[])
Median_Filter.
Definition: median_filter.h:82
bool new_status_message
vector< double > measures
optoelectric::sensor_sharp_msg sharp_msg
Median filter code implementation.
void SensorCallback(const optoelectric::sensor_sharp_msg &msg)
SensorCallback.


atlascar_egomotion
Author(s): Pedro Salvado
autogenerated on Mon Mar 2 2015 01:31:26