Allow to choose output precision in tf_echo (#186)
* Allow to choose output precision in tf_echo
Victor Lamoine authored 5 years ago
Tully Foote committed 5 years ago
69 | 69 | return -1; |
70 | 70 | } |
71 | 71 | |
72 | ros::NodeHandle nh; | |
72 | ros::NodeHandle nh("~"); | |
73 | 73 | |
74 | 74 | double rate_hz; |
75 | 75 | if (argc == 4) |
80 | 80 | else |
81 | 81 | { |
82 | 82 | // read rate parameter |
83 | ros::NodeHandle p_nh("~"); | |
84 | p_nh.param("rate", rate_hz, 1.0); | |
83 | nh.param("rate", rate_hz, 1.0); | |
85 | 84 | } |
86 | 85 | if (rate_hz <= 0.0) |
87 | 86 | { |
89 | 88 | return -1; |
90 | 89 | } |
91 | 90 | ros::Rate rate(rate_hz); |
91 | ||
92 | int precision(3); | |
93 | if (nh.getParam("precision", precision)) | |
94 | { | |
95 | if (precision < 1) | |
96 | { | |
97 | std::cerr << "Precision must be > 0\n"; | |
98 | return -1; | |
99 | } | |
100 | printf("Precision default value was overriden, new value: %d\n", precision); | |
101 | } | |
92 | 102 | |
93 | 103 | //Instantiate a local listener |
94 | 104 | echoListener echoListener; |
109 | 119 | { |
110 | 120 | tf::StampedTransform echo_transform; |
111 | 121 | echoListener.tf.lookupTransform(source_frameid, target_frameid, ros::Time(), echo_transform); |
112 | std::cout.precision(3); | |
122 | std::cout.precision(precision); | |
113 | 123 | std::cout.setf(std::ios::fixed,std::ios::floatfield); |
114 | 124 | std::cout << "At time " << echo_transform.stamp_.toSec() << std::endl; |
115 | 125 | double yaw, pitch, roll; |