This package is an alternative to official ROS node tf/tf_remap with the following advantages:
/tf_static
**new
)/tf_old
and remapping and publishing them to /tf
, but it can also watch /tf
, perform a reverse remapping, and publish new TF messages to /tf_old
/map
frame), and then you have a multirobot coordination algorithm which wants to see the maps of each robot as /ugv1/map
, /ugv2/map
and so on, and also wants to publish a /global_map
frame available to all robots.tf
to tf_remapper_cpp
in your launch fileslibtf_remapper_cpp.so
, class TfRemapper
The node that performs the TF remapping.
mappings
** (array of dicts
): The rules for TF frame name remapping, e.g. [{"old": "b", "new": "d"}]
. Each dict presents one remapping rule. Each dict contains keys old
and new
. If either of these keys is missing or its value is empty string, it means the TF frame should be deleted.rosrun
commandline - either set it in a launch file, or use `rosparam set /tf_remapper/mappings '[{"old": "b", "new": "d"}]'before launching this node.
**
static_tf** (
bool): Whether the remapper acts on static TFs or not. If not set, it is autodetected from
new_tf_topic_name` parameter.new_tf_topic_name
is tf_static
or /tf_static
, and if it is, then static_tf
is set to True
, otherwise it is set to False
.old_tf_topic_name
** (string
, default `'/tf_old'): The topic on which old TFs are subscribed.
**
new_tf_topic_name** (
string, default
'/tf'): The topic on which remapped TFs are published.
**
is_bidirectional** (
bool, default
False): If
True`, the remapper will also allow passing TFs published on the "remapped end" to the "old end" via a reverse mapping./tf_old
** (or any other topic set in old_tf_topic_name
; type tf2_ros/TFMessage
): The original TF messages that are to be remapped./tf
** (or any other topic set in new_tf_topic_name
; only if is_bidirectional == True
; type tf2_ros/TFMessage
): The TF messages with remapped frames. If some node publises to this topic and this remapper is running in bidirectional mode, it sends the newly published transforms back to /tf_old
./tf
** (or any other topic set in new_tf_topic_name
; type tf2_ros/ TFMessage
): The TF messages with remapped frames./tf_old
** (or any other topic set in old_tf_topic_name
; only if is_bidirectional == True
; type tf2_ros/TFMessage
): The original TF messages. If some node publises to /tf
and this remapper is running in bidirectional mode, it sends the newly published transforms back to this topic.<launch> <group> <remap from="tf" to="tf_old" /> <node name="broadcaster_ab" pkg="tf" type="static_transform_publisher" args="1 2 3 4 5 6 a b 10"/> </group> <node name="remapper" pkg="tf_remapper_cpp" type="tf_remap"> <rosparam param="mappings">[{old: b, new: c}]</rosparam> </node> <node name="my_node" pkg="my_pkg" type="node_type" /> </launch>
<launch> <group> <remap from="tf_static" to="tf_static_old" /> <node name="broadcaster_ab" pkg="tf2_ros" type="static_transform_publisher" args="1 2 3 4 5 6 a b"/> </group> <node name="remapper" pkg="tf_remapper_cpp" type="tf_remap"> <rosparam param="mappings">[{old: b, new: c}]</rosparam> </node> <node name="my_node" pkg="my_pkg" type="node_type" /> </launch>
<launch> <group> <remap from="tf" to="tf_old" /> <node name="broadcaster_ab" pkg="tf" type="static_transform_publisher" args="1 2 3 4 5 6 a b 10"/> <node name="my_node2" pkg="my_pkg" type="node_type" /> </group> <node name="remapper" pkg="tf_remapper_cpp" type="tf_remap"> <rosparam param="mappings">[{old: b, new: c}, {old: e, new: f}]</rosparam> <param name="is_bidirectional" value="true" /> </node> <node name="my_node" pkg="my_pkg" type="node_type" /> <node name="broadcaster_df" pkg="tf" type="static_transform_publisher" args="1 2 3 4 5 6 d f 10"/> </launch>