ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Unable to publish multiple static transformations using tf

asked 2018-04-04 06:08:06 -0500

ravijoshi gravatar image

I have 10 static transformations. Each one is saved in a separate yaml file. I want to publish these transformations using StaticTransformBroadcaster. Please see the code snippet below-

def main():
    # create tf static transform broadcaster
    tf_broadcaster = tf2_ros.StaticTransformBroadcaster()

    for i in range(10):
        calibFile = str(i) + '_calibration.yaml'

        with open(calibFile, 'r') as f:
            params = yaml.load(f)

        static_transformStamped = TransformStamped()

        static_transformStamped.header.stamp = rospy.Time.now()
        static_transformStamped.header.frame_id = params['parent']
        static_transformStamped.child_frame_id = params['child']

        static_transformStamped.transform.translation = params['trans']
        static_transformStamped.transform.rotation = params['rot']

        # publish static transformation
        tf_broadcaster.sendTransform(static_transformStamped)

    # infinite loop
    rospy.spin()

Iteratively I am reading each transform and then by using tf, I am trying to publish them. However, the above code doesn't work. It just publishes the last transform only.

My objective is to publish all static transformations. I am using ROS Indigo on Ubuntu 14.04 LTS OS.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
6

answered 2018-04-04 06:55:15 -0500

gvdhoorn gravatar image

updated 2018-04-04 13:00:39 -0500

I believe you're running into a peculiarity / TF2 specific characteristic of static transform publishers. From #q261815:

Since it's a latched topic it's recommended to only have one Static Transform Publisher per process.

You can resolve this by sending multiple transforms at once via a single broadcaster.

br.sendTransform([t,t2])
edit flag offensive delete link more

Comments

2

Thanks a lot. It worked like a charm.

ravijoshi gravatar image ravijoshi  ( 2018-04-04 21:41:12 -0500 )edit
1

answered 2018-04-04 12:07:44 -0500

Gayan Brahmanage gravatar image

updated 2018-04-04 12:09:54 -0500

Try with the following piece of codes

import rospy
import roslib
import tf


def handle_transform(parent, child, tr):
    br.sendTransform((tr[0], tr[1], 0), tf.transformations.quaternion_from_euler(0, 0, tr[2]), rospy.Time.now(), child,parent)

if __name__ == "__main__":


    rospy.init_node('tfpublisher', anonymous=True) #make node
    rate = rospy.Rate(10) # 5hz

    br = tf.TransformBroadcaster() 
    while not rospy.is_shutdown():

        handle_transform("base_link", "scans", [0,0,0])     

        rate.sleep()
edit flag offensive delete link more

Comments

This seems to use tf, not tf2. Static transforms are handled differently between the two.

gvdhoorn gravatar image gvdhoorn  ( 2018-04-04 13:00:24 -0500 )edit

Thank you very much. I upvoted your suggestion. However, it is better to use StaticTransformBroadcaster from tf2.

ravijoshi gravatar image ravijoshi  ( 2018-04-04 21:42:53 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-04-04 06:08:06 -0500

Seen: 3,339 times

Last updated: Apr 04 '18