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 if (rate_hz <= 0.0)
00088 {
00089 std::cerr << "Echo rate must be > 0.0\n";
00090 return -1;
00091 }
00092 ros::Rate rate(rate_hz);
00093
00094
00095 echoListener echoListener;
00096
00097
00098 std::string source_frameid = std::string(argv[1]);
00099 std::string target_frameid = std::string(argv[2]);
00100
00101
00102 echoListener.tf.waitForTransform(source_frameid, target_frameid, ros::Time(), ros::Duration(1.0));
00103
00104
00105
00106
00107 while(nh.ok())
00108 {
00109 try
00110 {
00111 tf::StampedTransform echo_transform;
00112 echoListener.tf.lookupTransform(source_frameid, target_frameid, ros::Time(), echo_transform);
00113 std::cout.precision(3);
00114 std::cout.setf(std::ios::fixed,std::ios::floatfield);
00115 std::cout << "At time " << echo_transform.stamp_.toSec() << std::endl;
00116 double yaw, pitch, roll;
00117 echo_transform.getBasis().getRPY(roll, pitch, yaw);
00118 tf::Quaternion q = echo_transform.getRotation();
00119 tf::Vector3 v = echo_transform.getOrigin();
00120 std::cout << "- Translation: [" << v.getX() << ", " << v.getY() << ", " << v.getZ() << "]" << std::endl;
00121 std::cout << "- Rotation: in Quaternion [" << q.getX() << ", " << q.getY() << ", "
00122 << q.getZ() << ", " << q.getW() << "]" << std::endl
00123 << " in RPY (radian) [" << roll << ", " << pitch << ", " << yaw << "]" << std::endl
00124 << " in RPY (degree) [" << roll*180.0/M_PI << ", " << pitch*180.0/M_PI << ", " << yaw*180.0/M_PI << "]" << std::endl;
00125
00126
00127 }
00128 catch(tf::TransformException& ex)
00129 {
00130 std::cout << "Failure at "<< ros::Time::now() << std::endl;
00131 std::cout << "Exception thrown:" << ex.what()<< std::endl;
00132 std::cout << "The current list of frames is:" <<std::endl;
00133 std::cout << echoListener.tf.allFramesAsString()<<std::endl;
00134
00135 }
00136 rate.sleep();
00137 }
00138
00139 return 0;
00140 };
00141