tf_echo.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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   //constructor with name
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   //Initialize ROS
00059   ros::init(argc, argv, "tf_echo", ros::init_options::AnonymousName);
00060 
00061   // Allow 2 or 3 command line arguments
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     // read rate from command line
00078     rate_hz = atof(argv[3]);
00079   }
00080   else
00081   {
00082     // read rate parameter
00083     ros::NodeHandle p_nh("~");
00084     p_nh.param("rate", rate_hz, 1.0);
00085   }
00086   ros::Rate rate(rate_hz);
00087 
00088   //Instantiate a local listener
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   // Wait for up to one second for the first transforms to become avaiable. 
00096   echoListener.tf.waitForTransform(source_frameid, target_frameid, ros::Time(), ros::Duration(1.0));
00097 
00098   //Nothing needs to be done except wait for a quit
00099   //The callbacks withing the listener class
00100   //will take care of everything
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         //print transform
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 


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 27 2015 13:02:09