Codebase list ros-geometry / e7b7118
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
1 changed file(s) with 14 addition(s) and 4 deletion(s). Raw diff Collapse all Expand all
6969 return -1;
7070 }
7171
72 ros::NodeHandle nh;
72 ros::NodeHandle nh("~");
7373
7474 double rate_hz;
7575 if (argc == 4)
8080 else
8181 {
8282 // 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);
8584 }
8685 if (rate_hz <= 0.0)
8786 {
8988 return -1;
9089 }
9190 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 }
92102
93103 //Instantiate a local listener
94104 echoListener echoListener;
109119 {
110120 tf::StampedTransform echo_transform;
111121 echoListener.tf.lookupTransform(source_frameid, target_frameid, ros::Time(), echo_transform);
112 std::cout.precision(3);
122 std::cout.precision(precision);
113123 std::cout.setf(std::ios::fixed,std::ios::floatfield);
114124 std::cout << "At time " << echo_transform.stamp_.toSec() << std::endl;
115125 double yaw, pitch, roll;