00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #include <atlascar_egomotion/median_filter.h>
00033 optoelectric::sensor_sharp_msg sharp_msg;
00034 vector<double> measures;
00035 bool new_status_message;
00036
00043 void SensorCallback (const optoelectric::sensor_sharp_msg &msg)
00044 {
00045
00046 sharp_msg=msg;
00047 new_status_message=true;
00048
00049 }
00054 int main(int argc,char**argv)
00055 {
00056
00057 ros::init(argc, argv, "sensor_sharp_transformation_node");
00058 ros::NodeHandle n;
00059 ros::Subscriber sensor_msg_subs= n.subscribe("/snr/opto/sensor",1, SensorCallback);
00060 ros::Rate r(60.0);
00061
00062 int count_f_l=0;
00063 int count_f_r=0;
00064 int count_b_l=0;
00065 int count_b_r=0;
00066 float d_front_left_array[8];
00067 float d_front_right_array[8];
00068 float d_back_left_array[8];
00069 float d_back_right_array[8];
00070 while(n.ok())
00071 {
00072 spinOnce();
00073 r.sleep();
00074 if(!new_status_message)
00075 continue;
00076
00077 new_status_message=false;
00078
00079
00080 float dist_front_left=Median_Filter(count_f_l,sharp_msg.d_front_left,d_front_left_array);
00081 count_f_l++;
00082
00083 float dist_front_right=Median_Filter(count_f_r,sharp_msg.d_front_right,d_front_right_array);
00084 count_f_r++;
00085
00086 float dist_back_left=Median_Filter(count_b_l,sharp_msg.d_back_left,d_back_left_array);
00087 count_b_l++;
00088
00089 float dist_back_right=Median_Filter(count_b_r,sharp_msg.d_back_right,d_back_right_array);
00090 count_b_r++;
00091
00092
00093 float z_mean=(dist_front_left + dist_front_right + dist_back_left + dist_back_right)/4;
00094 float roll_front=atan2((dist_front_left - dist_front_right),1.27);
00095 float roll_back=atan2((dist_back_left - dist_back_right),0.67);
00096
00097 float pitch=atan2((dist_back_left + dist_back_right)*0.5 - (dist_front_left + dist_front_right)*0.5,1.39*2);
00098 static tf::TransformBroadcaster br;
00099 tf::Transform transform;
00100 transform.setOrigin( tf::Vector3(0.0, 0.0, z_mean) );
00101 transform.setRotation(tf::createQuaternionFromRPY((roll_front+roll_back)*0.5, pitch, 0) );
00102 br.sendTransform(tf::StampedTransform(transform, sharp_msg.header.stamp,"/ground", "/atc/vehicle/center_car_axis" ));
00103
00104 }
00105
00106 return 0;
00107 }
00108