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