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   if (argc != 3)
00062   {
00063     printf("Usage: tf_echo source_frame target_frame\n\n");
00064     printf("This will echo the transform from the coordinate frame of the source_frame\n");
00065     printf("to the coordinate frame of the target_frame. \n");
00066     printf("Note: This is the transform to get data from target_frame into the source_frame.\n");
00067     return -1;
00068   }
00069 
00070   ros::NodeHandle nh;
00071   //Instantiate a local listener
00072   echoListener echoListener;
00073 
00074 
00075   std::string source_frameid = std::string(argv[1]);
00076   std::string target_frameid = std::string(argv[2]);
00077 
00078   // Wait for up to one second for the first transforms to become avaiable. 
00079   echoListener.tf.waitForTransform(source_frameid, target_frameid, ros::Time(), ros::Duration(1.0));
00080 
00081   //Nothing needs to be done except wait for a quit
00082   //The callbacks withing the listener class
00083   //will take care of everything
00084   while(nh.ok())
00085     {
00086       try
00087       {
00088         tf::StampedTransform echo_transform;
00089         echoListener.tf.lookupTransform(source_frameid, target_frameid, ros::Time(), echo_transform);
00090         std::cout.precision(3);
00091         std::cout.setf(std::ios::fixed,std::ios::floatfield);
00092         std::cout << "At time " << echo_transform.stamp_.toSec() << std::endl;
00093         double yaw, pitch, roll;
00094         echo_transform.getBasis().getRPY(roll, pitch, yaw);
00095         tf::Quaternion q = echo_transform.getRotation();
00096         tf::Vector3 v = echo_transform.getOrigin();
00097         std::cout << "- Translation: [" << v.getX() << ", " << v.getY() << ", " << v.getZ() << "]" << std::endl;
00098         std::cout << "- Rotation: in Quaternion [" << q.getX() << ", " << q.getY() << ", " 
00099                   << q.getZ() << ", " << q.getW() << "]" << std::endl
00100                   << "            in RPY [" <<  roll << ", " << pitch << ", " << yaw << "]" << std::endl;
00101 
00102         //print transform
00103       }
00104       catch(tf::TransformException& ex)
00105       {
00106         std::cout << "Failure at "<< ros::Time::now() << std::endl;
00107         std::cout << "Exception thrown:" << ex.what()<< std::endl;
00108         std::cout << "The current list of frames is:" <<std::endl;
00109         std::cout << echoListener.tf.allFramesAsString()<<std::endl;
00110         
00111       }
00112       sleep(1);
00113     }
00114 
00115   return 0;
00116 };
00117 


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 6 2014 00:12:04