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

Revision history [back]

Your data looks like a ROS tf2 transform... or a "pose": is that where you got it from ?

Anyway, "tf"s are well visualised in RVIZ: so if that was the source, just select it in RVIZ.

If from other source, you can use python to put it into tf-format, broadcast it, and then see in RVIZ.

If this is of interest, I can post some sample code.

Your I assume your data looks like is from a ROS tf2 transform... or a odometry "pose": is that where you got it from ? or where from ?

Anyway, "tf"s are Normally a robot's pose is broadcast as a ROS tf transform, which is well visualised in RVIZ: so if that was the source, just select it in RVIZ.

If from other source, you can use python to put it into tf-format, broadcast it, and then see in RVIZ.

If this is of interest, I can post some sample code.code to put odom pose into a tf.

I assume your data is from a ROS odometry "pose": is that where you got it from ? or where from ?

Normally a robot's pose is broadcast as a ROS tf transform, which is well visualised in RVIZ: so if that was the source, just select it in RVIZ.

If from other source, you can use python to put it into tf-format, broadcast it, and then see in RVIZ.

If this is of interest, I can post some sample code to put odom pose into a tf.

tf. e.g. this worked for me:

#!/usr/bin/env python3

import rospy
import tf2_ros
from nav_msgs.msg import Odometry
from geometry_msgs.msg import TransformStamped

rospy.init_node("posetf")
tf_buffer = tf2_ros.Buffer(cache_time=rospy.Duration(4))
tf_listener = tf2_ros.TransformListener(tf_buffer)
br = tf2_ros.TransformBroadcaster()

def get_odom(msg):                      # CallBack: at ~ 30 Hz nav.message ...
    # ================ broadcast new tf : transout =======
    transout = TransformStamped()
    transout.header.stamp = msg.header.stamp
    transout.header.frame_id = msg.header.frame_id          # e.g. this is likely "odom" frame
    transout.child_frame_id = "newpose"
    transout.transform.translation = msg.pose.pose.position
    transout.transform.rotation = msg.pose.pose.orientation
    br.sendTransform(transout)

# ===================================  Start subscribers etc ... ========================================
rospy.Subscriber('/odom', Odometry, get_odom, queue_size=1)     # nav_msgs/Odometry
rospy.spin()

The "newpose" tf then simply appears in RVIZ list of TF Frames ... easy to see as it moves around...