Go to the documentation of this file.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 
00027 
00028 
00029 
00030 #include <cstdio>
00031 #include "tf/transform_listener.h"
00032 #include "ros/ros.h"
00033 
00034 class echoListener
00035 {
00036 public:
00037 
00038   tf::TransformListener tf;
00039 
00040   
00041   echoListener()
00042   {
00043 
00044   };
00045 
00046   ~echoListener()
00047   {
00048 
00049   };
00050 
00051 private:
00052 
00053 };
00054 
00055 
00056 int main(int argc, char ** argv)
00057 {
00058   
00059   ros::init(argc, argv, "tf_echo", ros::init_options::AnonymousName);
00060 
00061   
00062   if (argc < 3 || argc > 4)
00063   {
00064     printf("Usage: tf_echo source_frame target_frame [echo_rate]\n\n");
00065     printf("This will echo the transform from the coordinate frame of the source_frame\n");
00066     printf("to the coordinate frame of the target_frame. \n");
00067     printf("Note: This is the transform to get data from target_frame into the source_frame.\n");
00068     printf("Default echo rate is 1 if echo_rate is not given.\n");
00069     return -1;
00070   }
00071 
00072   ros::NodeHandle nh;
00073 
00074   double rate_hz;
00075   if (argc == 4)
00076   {
00077     
00078     rate_hz = atof(argv[3]);
00079   }
00080   else
00081   {
00082     
00083     ros::NodeHandle p_nh("~");
00084     p_nh.param("rate", rate_hz, 1.0);
00085   }
00086   ros::Rate rate(rate_hz);
00087 
00088   
00089   echoListener echoListener;
00090 
00091 
00092   std::string source_frameid = std::string(argv[1]);
00093   std::string target_frameid = std::string(argv[2]);
00094 
00095   
00096   echoListener.tf.waitForTransform(source_frameid, target_frameid, ros::Time(), ros::Duration(1.0));
00097 
00098   
00099   
00100   
00101   while(nh.ok())
00102     {
00103       try
00104       {
00105         tf::StampedTransform echo_transform;
00106         echoListener.tf.lookupTransform(source_frameid, target_frameid, ros::Time(), echo_transform);
00107         std::cout.precision(3);
00108         std::cout.setf(std::ios::fixed,std::ios::floatfield);
00109         std::cout << "At time " << echo_transform.stamp_.toSec() << std::endl;
00110         double yaw, pitch, roll;
00111         echo_transform.getBasis().getRPY(roll, pitch, yaw);
00112         tf::Quaternion q = echo_transform.getRotation();
00113         tf::Vector3 v = echo_transform.getOrigin();
00114         std::cout << "- Translation: [" << v.getX() << ", " << v.getY() << ", " << v.getZ() << "]" << std::endl;
00115         std::cout << "- Rotation: in Quaternion [" << q.getX() << ", " << q.getY() << ", " 
00116                   << q.getZ() << ", " << q.getW() << "]" << std::endl
00117                   << "            in RPY [" <<  roll << ", " << pitch << ", " << yaw << "]" << std::endl;
00118 
00119         
00120       }
00121       catch(tf::TransformException& ex)
00122       {
00123         std::cout << "Failure at "<< ros::Time::now() << std::endl;
00124         std::cout << "Exception thrown:" << ex.what()<< std::endl;
00125         std::cout << "The current list of frames is:" <<std::endl;
00126         std::cout << echoListener.tf.allFramesAsString()<<std::endl;
00127         
00128       }
00129       rate.sleep();
00130     }
00131 
00132   return 0;
00133 };
00134