ros / geometry

Packages for common geometric calculations including the ROS transform library, "tf". Also includes ROS bindings for "bullet" physics engine and "kdl" kinematics/dynamics package.
173 stars 274 forks source link

Allow to choose output precision in tf_echo #186

Closed VictorLamoine closed 5 years ago

VictorLamoine commented 5 years ago

Improves #171

With this PR it is possible to choose the precision of the pose output by passing an argument to the node:

rosrun tf tf_echo base tool0 _precision:=12

I am inspecting robot poses and I need at least millimeter precision. This allows getting the precision without cluttering the default output.

Example run:

$ rosrun tf tf_echo base tool0 _precision:=8
[ INFO] [1556030892.141355409]: Precision: 8
Failure at 1556030893.154955017
Exception thrown:Could not find a connection between 'base' and 'tool0' because they are not part of the same tree.Tf has two or more unconnected trees.
The current list of frames is:
Frame base exists with parent base_link.
Frame flange exists with parent link_6.
Frame tool0 exists with parent link_6.

Failure at 1556030893.155026131
Exception thrown:Could not find a connection between 'base' and 'tool0' because they are not part of the same tree.Tf has two or more unconnected trees.
The current list of frames is:
Frame base exists with parent base_link.
Frame flange exists with parent link_6.
Frame tool0 exists with parent link_6.

At time 1556030893.30690527
- Translation: [1.62458820, -0.14177884, 0.48463830]
- Rotation: in Quaternion [0.70637963, 0.70496671, -0.05111242, 0.03791152]
            in RPY (radian) [-3.12293846, 0.12599536, 1.56997085]
            in RPY (degree) [-178.93119320, 7.21900259, 89.95270386]
VictorLamoine commented 5 years ago

I've done modifications to fix what you suggest. I'll look at the tf2_tools and try to add the same functionality!


It's here: https://github.com/ros/geometry2/pull/377