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

tf2 conversion of geometry message

asked 2018-12-20 04:49:27 -0500

felix.behnke gravatar image

Hi,

I am new to ROS and try to figure out how to use tf2 for my purpose.

I want to have a fixed map frame in which I publish a gravity vector with datatype Vector3Stamped: [0,0,9.81] Next I have a sensor frame which is rotated by TransformBroadcaster.

How can i now ask for the gravity vector in respect to the rotated sensor frame? If both frames are aligned it should also be [0,0,9.81] but should change with rotation.

The rotation of the sensor frame is working fine and I can watch it in RVIZ. It is just the part, getting the corresponding vector in my other frame which i cannot figure out by the tutorials and documentation.

How exactly do i have to publish the vector?

... my approach:

Publisher:

gravity_pub = rospy.Publisher('gravity', geometry_msgs.msg.Vector3Stamped, queue_size = 1)
# TF Publisher:
g = geometry_msgs.msg.Vector3Stamped()
# Header:
g.header.stamp = rospy.Time.now()
g.header.frame_id = 'sensor'
# Data:
g.vector.x = 0
g.vector.y = 0
g.vector.z = 9.81

gravity_pub.publish(g)

Listener:

rospy.init_node('tf2_imu_listener')
tfBuffer = tf2_ros.Buffer()
listener = tf2_ros.TransformListener(tfBuffer)
trans = tfBuffer.lookup_vector('map', 'imu', rospy.Time())
print trans

Thank you very much for your help!

Felix

edit retag flag offensive close merge delete

Comments

g.header.frame_id = 'sensor'

Wouldn't this make your "gravity frame" relative to your "sensor" frame? I would expect you to publish a gravity vector in some world/map/global frame and then transform that into the sensor frame, but I may be misunderstanding your question.

gvdhoorn gravatar image gvdhoorn  ( 2018-12-20 05:41:29 -0500 )edit
1

I'd also note that gravity is a direction, so would be more meaningfully represented by the orientation of a pose. This way if it is rotated and translated to different frames the direction will still be correct. A vector defines a location, so a translation will alter the direction it's pointing.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-12-20 09:13:45 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-12-21 04:01:08 -0500

felix.behnke gravatar image

I already figured out, what i searched for. Its a built in function of tfBuffer:

tfBuffer = tf2_ros.Buffer()
listener = tf2_ros.TransformListener(tfBuffer)

acc_local = Vector3Stamped(header=imu_msg.header, vector=imu_msg.linear_acceleration)
acc_global = tfBuffer.transform(acc_local, 'fixed', timeout=rospy.Duration(0.1))

something like this. Thanks for the help!

edit flag offensive delete link more

Question Tools

Stats

Asked: 2018-12-20 04:49:27 -0500

Seen: 487 times

Last updated: Dec 21 '18