00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00032 #include<tf/transform_listener.h> 00033 #include <nav_msgs/Odometry.h> 00034 #include <sensor_msgs/Imu.h> 00035 #include "geometry_msgs/Pose.h" 00036 #include "geometry_msgs/Quaternion.h" 00037 #include "tf/transform_datatypes.h" 00038 #include <stdio.h> 00039 #include <tf/transform_broadcaster.h> 00040 ros::Publisher odom_pub; 00041 nav_msgs::Odometry odometry_; 00042 using namespace std; 00043 00044 #define PFLN {printf("%s %d\n",__FILE__, __LINE__);} 00045 tf::TransformBroadcaster *p_odom_broadcaster; 00046 sensor_msgs::Imu imu_data; 00047 //tf::TransformBroadcaster *p_tf_broadcaster; 00048 tf::TransformListener *p_listener; 00049 00050 //FILE * pFile; 00051 00052 //this 00053 void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg ) 00054 { 00055 imu_data=*msg; 00056 } 00057 int main(int argc, char** argv) 00058 { 00059 // pFile=fopen("../alboi_final_pos.txt","w+"); 00060 ros::init(argc, argv, "robot_pose2odometry"); 00061 ros::NodeHandle n; 00062 odom_pub = n.advertise<nav_msgs::Odometry>("/robot_pose_odometry", 50); 00063 ros::Subscriber imu= n.subscribe("/atc/imu/data",1, ImuCallback); 00064 tf::TransformListener listener; 00065 //p_listener=&listener; 00066 tf::TransformBroadcaster odom_broadcaster; 00067 ros::Rate r(40.0); 00068 while(n.ok()) 00069 { 00070 ros::spinOnce(); 00071 r.sleep(); 00072 //intersect transformation by robot_pose_ekf 00073 bool have_transform=false; 00074 tf::StampedTransform transform_robot_pose_ekf; 00075 try 00076 { 00077 listener.lookupTransform("/world","/base_footprint" , ros::Time(0), transform_robot_pose_ekf); 00078 have_transform=true; 00079 } 00080 catch (tf::TransformException ex) 00081 { 00082 if(listener.waitForTransform("/world","/base_footprint",ros::Time(0), ros::Duration(3.0))) 00083 { 00084 try 00085 { 00086 listener.lookupTransform("/world","/base_footprint" , ros::Time(0), transform_robot_pose_ekf); 00087 have_transform=true; 00088 } 00089 catch (tf::TransformException ex) 00090 { 00091 ROS_ERROR("Could not lookup transform after waiting 3 secs\n.%s",ex.what()); 00092 } 00093 } 00094 else 00095 { 00096 ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what()); 00097 } 00098 } 00099 00100 if (have_transform==false) 00101 { 00102 //return; 00103 continue; 00104 } 00105 /* 00106 //intersect transformation from center_car_axes to /road_plane 00107 bool have_transform_2=false; 00108 tf::StampedTransform transform2ground; 00109 try 00110 { 00111 listener.lookupTransform("/ground","/atc/vehicle/center_car_axes" , ros::Time(0), transform2ground); 00112 have_transform_2=true; 00113 } 00114 catch (tf::TransformException ex) 00115 { 00116 if(listener.waitForTransform("/ground","/atc/vehicle/center_car_axes",ros::Time(0), ros::Duration(3.0))) 00117 { 00118 try 00119 { 00120 listener.lookupTransform("/ground","/atc/vehicle/center_car_axes" , ros::Time(0), transform2ground); 00121 have_transform_2=true; 00122 } 00123 catch (tf::TransformException ex) 00124 { 00125 ROS_ERROR("Could not lookup transform after waiting 3 secs\n.%s",ex.what()); 00126 } 00127 } 00128 else 00129 { 00130 ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what()); 00131 } 00132 } 00133 00134 if (have_transform_2==false) 00135 { 00136 //return; 00137 continue; 00138 } 00139 00140 //get roll pitch yaw from transform2ground 00141 double roll_2,pitch_2,yaw_2; 00142 btQuaternion q_2 = transform2ground.getRotation(); 00143 btMatrix3x3(q_2).getRPY(roll_2, pitch_2, yaw_2); 00144 */ 00145 00146 //get roll pitch yaw from transform_robot_pose_ekf 00147 double roll_1,pitch_1,yaw_1; 00148 tf::Quaternion q1 = transform_robot_pose_ekf.getRotation(); 00149 tf::Matrix3x3(q1).getRPY(roll_1, pitch_1, yaw_1); 00150 static tf::TransformBroadcaster br; 00151 tf::Transform transform; 00152 transform.setOrigin( tf::Vector3((transform_robot_pose_ekf.getOrigin()).x(), (transform_robot_pose_ekf.getOrigin()).y(), 0) ); 00153 transform.setRotation(tf::createQuaternionFromRPY(0.0,0.0, yaw_1) ); 00154 //transform.setRotation(tf::createQuaternionFromRPY(0.0,0.0, yaw_1) ); 00155 br.sendTransform(tf::StampedTransform(transform, transform_robot_pose_ekf.stamp_,"/world", "/ground" )); 00156 00157 // fprintf(pFile,"%0.5f %0.5f\n", (transform_robot_pose_ekf.getOrigin()).x(), (transform_robot_pose_ekf.getOrigin()).y()); 00158 } 00159 // fclose(pFile); 00160 return 0; 00161 }