Sometimes, there is a need to quickly set up a static transform in ROS. To avoid manually searching for translation and rotation parameters, we have written this minimalistic tool that allows us to do it a more convenient, click-and-drag way.
The Problem
The physical configuration of a robot can change or a new sensor is added.
Since this configuration is reflected by the ROS TF system, the corresponding static transform needs to be updated.
The classical approach would be trial-and-error with the comand line rosrun tf static_transform_publisher [params]
, looking for the right numbers.
It is tedious, unnecessary and there is a better way to do this.
Solution - Interactive Static Transform tool
Following the RVIZ Interactive Marker Tutorial, a simple tool was written. It helps in finding a transformation between two TF frames by providing an RVIZ interactive marker. Its usage is straightforward:
- Set your parent and child frame names in the launch file.
- Run the launch file and also open the RVIZ.
- The initial transformation is an identity, but you can modify it by displaying the interactive marker and moving it around.
- The marker also offers a context menu, the only command which is there
prints the current transform value in the form of the
static_transform_publisher
rosrun command.
The launch file and the code is placed within the norlab_imu_tools package:
<launch>
<node pkg="norlab_imu_tools" type="interactive_static_transform_publisher.py" name="interactive_static_transform_publisher_node" output="screen">
<param name="child_frame" value="moving_frame" />
<param name="parent_frame" value="base_link" />
<param name="tf_publish_period_in_sec" value="0.1" />
</node>
</launch>
The final transform output can be copied and pasted into a terminal or just used to set a new launch file:
[INFO] [1556661102.899894]: The equivalent static transform command:
[INFO] [1556661102.902316]: rosrun tf static_transform_publisher 1.92549085617 0.0 1.12673556805 0.327530413866 -0.155546739697 -0.399795621634 0.841839015484 base_link moving_frame 100