ground_attitude2world.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 ***************************************************************************************************/
32 #include<tf/transform_listener.h>
33 #include <nav_msgs/Odometry.h>
34 #include <sensor_msgs/Imu.h>
35 #include "geometry_msgs/Pose.h"
36 #include "geometry_msgs/Quaternion.h"
37 #include "tf/transform_datatypes.h"
38 #include <stdio.h>
39 #include <tf/transform_broadcaster.h>
40 ros::Publisher odom_pub;
41 nav_msgs::Odometry odometry_;
42 using namespace std;
43 
44 #define PFLN {printf("%s %d\n",__FILE__, __LINE__);}
45 tf::TransformBroadcaster *p_odom_broadcaster;
46 sensor_msgs::Imu imu_data;
47 //tf::TransformBroadcaster *p_tf_broadcaster;
48 tf::TransformListener *p_listener;
49 
50 //FILE * pFile;
51 
52 //this
53 void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg )
54 {
55  imu_data=*msg;
56 }
57 int main(int argc, char** argv)
58 {
59 // pFile=fopen("../alboi_final_pos.txt","w+");
60  ros::init(argc, argv, "robot_pose2odometry");
61  ros::NodeHandle n;
62  odom_pub = n.advertise<nav_msgs::Odometry>("/robot_pose_odometry", 50);
63  ros::Subscriber imu= n.subscribe("/atc/imu/data",1, ImuCallback);
64  tf::TransformListener listener;
65  //p_listener=&listener;
66  tf::TransformBroadcaster odom_broadcaster;
67  ros::Rate r(40.0);
68  while(n.ok())
69  {
70  ros::spinOnce();
71  r.sleep();
72  //intersect transformation by robot_pose_ekf
73  bool have_transform=false;
74  tf::StampedTransform transform_robot_pose_ekf;
75  try
76  {
77  listener.lookupTransform("/world","/base_footprint" , ros::Time(0), transform_robot_pose_ekf);
78  have_transform=true;
79  }
80  catch (tf::TransformException ex)
81  {
82  if(listener.waitForTransform("/world","/base_footprint",ros::Time(0), ros::Duration(3.0)))
83  {
84  try
85  {
86  listener.lookupTransform("/world","/base_footprint" , ros::Time(0), transform_robot_pose_ekf);
87  have_transform=true;
88  }
89  catch (tf::TransformException ex)
90  {
91  ROS_ERROR("Could not lookup transform after waiting 3 secs\n.%s",ex.what());
92  }
93  }
94  else
95  {
96  ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what());
97  }
98  }
99 
100  if (have_transform==false)
101  {
102  //return;
103  continue;
104  }
105 /*
106  //intersect transformation from center_car_axes to /road_plane
107  bool have_transform_2=false;
108  tf::StampedTransform transform2ground;
109  try
110  {
111  listener.lookupTransform("/ground","/atc/vehicle/center_car_axes" , ros::Time(0), transform2ground);
112  have_transform_2=true;
113  }
114  catch (tf::TransformException ex)
115  {
116  if(listener.waitForTransform("/ground","/atc/vehicle/center_car_axes",ros::Time(0), ros::Duration(3.0)))
117  {
118  try
119  {
120  listener.lookupTransform("/ground","/atc/vehicle/center_car_axes" , ros::Time(0), transform2ground);
121  have_transform_2=true;
122  }
123  catch (tf::TransformException ex)
124  {
125  ROS_ERROR("Could not lookup transform after waiting 3 secs\n.%s",ex.what());
126  }
127  }
128  else
129  {
130  ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what());
131  }
132  }
133 
134  if (have_transform_2==false)
135  {
136  //return;
137  continue;
138  }
139 
140  //get roll pitch yaw from transform2ground
141  double roll_2,pitch_2,yaw_2;
142  btQuaternion q_2 = transform2ground.getRotation();
143  btMatrix3x3(q_2).getRPY(roll_2, pitch_2, yaw_2);
144 */
145 
146  //get roll pitch yaw from transform_robot_pose_ekf
147  double roll_1,pitch_1,yaw_1;
148  tf::Quaternion q1 = transform_robot_pose_ekf.getRotation();
149  tf::Matrix3x3(q1).getRPY(roll_1, pitch_1, yaw_1);
150  static tf::TransformBroadcaster br;
151  tf::Transform transform;
152  transform.setOrigin( tf::Vector3((transform_robot_pose_ekf.getOrigin()).x(), (transform_robot_pose_ekf.getOrigin()).y(), 0) );
153  transform.setRotation(tf::createQuaternionFromRPY(0.0,0.0, yaw_1) );
154  //transform.setRotation(tf::createQuaternionFromRPY(0.0,0.0, yaw_1) );
155  br.sendTransform(tf::StampedTransform(transform, transform_robot_pose_ekf.stamp_,"/world", "/ground" ));
156 
157  // fprintf(pFile,"%0.5f %0.5f\n", (transform_robot_pose_ekf.getOrigin()).x(), (transform_robot_pose_ekf.getOrigin()).y());
158  }
159 // fclose(pFile);
160  return 0;
161 }
tf::TransformBroadcaster * p_odom_broadcaster
tf::TransformListener * p_listener
sensor_msgs::Imu imu_data
ros::Publisher odom_pub
void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg)
int main(int argc, char **argv)
nav_msgs::Odometry odometry_


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