ros1_bridge icon indicating copy to clipboard operation
ros1_bridge copied to clipboard

Bridge wont latch for /tf_static for 2 to 1

Open geoeo opened this issue 3 years ago • 12 comments

When trying to publish a static tf via the ros2 broadcaster the message wont latch correctly. I.e when opening rviz after the publishing I can recover the tf tree. When I open it before jt works.

I run the bridge via a param file

geoeo avatar Aug 17 '22 13:08 geoeo

Can you please clarify what the problem is that you have encountered? Providing a minimal reproducible example would help us with reproducing your problem.

gbiggs avatar Aug 17 '22 20:08 gbiggs

I have a Ros2 pub and Ros 1 sub. The only topic I am publishing is a static transform once.

If I open Rviz after I have published the tf I cannot recover the tf tree. Rviz2 works which means its a bridge issue.

Ill provide some code when im at a different machine

geoeo avatar Aug 18 '22 09:08 geoeo

I cannot help you without knowing more about what your system is. Please post a repository that reproduces the problem.

gbiggs avatar Aug 18 '22 20:08 gbiggs

  • System : Ubuntu 20.04
  • ROS2: Galactic
  • Installation Type: From Apt
  • Client Library: Rclpy, tf2_ros

Shells in this Order

Shell 1:

# Shell A (ROS 1 only):
source ${ROS1_INSTALL_PATH}/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
roscore

Shell 2:

Shell B: (ROS 1 only):
source ${ROS1_INSTALL_PATH}/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
rosparam load bridge.yaml

Yaml Only Contains

topics:
  -
    topic: /tf_static
    type: tf2_msgs/msg/TFMessage
    queue_size: 1
    qos:
      history: keep_all
      durability: transient_local

Shell 3 - Node that publishes messages once (Python):

        from rclpy.node import Node
        from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
        
        ...
        class SomeNode(Node):
           def __init__(self):
                self.static_tf_publisher = StaticTransformBroadcaster(self)
                transformStamped = TransformStamped()
                time = self.get_clock().now()
                transformStamped.header.stamp = time.to_msg()
                self.camera_frame = 'camera'
                self.world_frame = 'world'
                transformStamped.header.frame_id = self.world_frame
                transformStamped.child_frame_id = self.camera_frame
                transformStamped.transform.translation.x = float(0)
                transformStamped.transform.translation.y = float(0)
                transformStamped.transform.translation.z = float(3)
                transformStamped.transform.rotation.x = 0.0
                transformStamped.transform.rotation.y = 0.0
                transformStamped.transform.rotation.z = 0.0
                transformStamped.transform.rotation.w = 1.0
                self.static_tf_publisher.sendTransform(transformStamped)
                
        def main(args=None):
              rclpy.init(args=args)
               some_node = SomeNode()

Shell 4 (Last) - The Static Tf is lost and the TF tree can not be recovered:

source ${ROS1_INSTALL_PATH}/setup.bash
ros run rviz rviz

geoeo avatar Aug 19 '22 07:08 geoeo

@geoeo Do you manage to solve your issue eventually?

Alex-Beh avatar Dec 15 '22 04:12 Alex-Beh

The problem is that transient_local topics from ROS 2 are not mapped to a latched topic in ROS 1. First I started to extend the create_bridge_from_2_to_1() method similar to the QoS settings from create_bridge_from_1_to_2, but then realized that this won't be enough:

Sometimes messages originate multiple publishers, for example /tf_static. When n ROS 2 messages are received by the bridge and published over a single ROS 1 latched publisher, only the last message will be sent when another node subscribes, independent of the queue size AFAIK.

For /tf_static there could be a special implementation that aggregates all incoming transformations on /tf_static and publishes a single, latched message. But this won't work in (rare) other scenarios with multiple publishers on the same topic.

maracuya-robotics avatar Mar 29 '23 10:03 maracuya-robotics

tf_static is been treated differently (hardcoded) already: https://github.com/ros2/ros1_bridge/pull/282

So that can be extended I guess. As you mention, other scenarios are rare and this bridge is meant is temporary solution/workaround :slightly_smiling_face:

Timple avatar Mar 30 '23 06:03 Timple

@Timple

tf_static is been treated differently (hardcoded) already: #282

That change affects only the ROS 1 to 2 direction by setting the QoS of the ROS 2 publisher to transient_local. This issue is about the ROS 1 publisher that must be latched and must also aggregate all /tf_static messages (because a subscriber to the latched ros1_bridge topic wants to receive all static transforms, even from multiple ROS 2 publishers).

maracuya-robotics avatar Mar 31 '23 06:03 maracuya-robotics

I know, I meant not literally extending that code part. You where wondering if you could treat tf_static as an exception.

I was trying to say that, within the scope of this ros1_bridge, the tf_static seems to be an exception already, so I don't see any problem with this.

Timple avatar Mar 31 '23 06:03 Timple

Having the same issue, did you solve the problem with static tf's not bridged?

weidinger-c avatar Dec 13 '23 10:12 weidinger-c

Hi same issue there, any news on this topic?

DanyResasco avatar Jul 11 '24 15:07 DanyResasco