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

tf2.LookupException: "map" passed to lookupTransform argument source_frame does not exist. [closed]

asked 2022-05-04 20:20:40 -0500

distro gravatar image

updated 2022-05-05 14:42:15 -0500

I am having an issue where for some reason my system says map frame does not exist. Here is the code here:

#!/usr/bin/env python2.7
import rospy
from nav_msgs.msg import Odometry
import sklearn
import numpy as np
from rospy.numpy_msg import numpy_msg
import math
import tf2_ros
import geometry_msgs.msg
import tf2_geometry_msgs
from geometry_msgs.msg import Point, PointStamped



def transform_point(transformation, point_wrt_source):
    point_wrt_target = \
        tf2_geometry_msgs.do_transform_point(PointStamped(point=point_wrt_source),
            transformation).point
    return [point_wrt_target.x, point_wrt_target.y]


def get_transformation(source_frame, target_frame,
                       tf_cache_duration=0.5):
    tf_buffer = tf2_ros.Buffer(rospy.Duration(tf_cache_duration))
    tf2_ros.TransformListener(tf_buffer)

    # get the tf at first available time
    #try:
    transformation = tf_buffer.lookup_transform(target_frame,source_frame, rospy.Time(0), rospy.Duration(0.1))
    #except (tf2_ros.LookupException, tf2_ros.ConnectivityException,
     #       tf2_ros.ExtrapolationException):
      #  rospy.logerr('Unable to find the transformation from %s to %s'% source_frame, target_frame)
    return transformation


def main(c):
    # initialize ros node
    rospy.init_node('tf2_ros_example')

    # define source and target frame
    source_frame = 'map'
    target_frame = 'base_footprint'

    # define a source point
    point_wrt_source = Point(c[0],c[1], 0)

    transformation = get_transformation(source_frame, target_frame)
    point_wrt_target = transform_point(transformation, point_wrt_source)
    print(point_wrt_target[0])


if __name__ == '__main__':
    main([2,1.2])

This is the error:

 ...main
    transformation = get_transformation(source_frame, target_frame)
  File "/home/philip/server_prac/src/action_practice/src/tester.py", line 29, in get_transformation
    transformation = tf_buffer.lookup_transform(target_frame,source_frame, rospy.Time(0), rospy.Duration(0.1))
  File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_ros/buffer.py", line 87, in lookup_transform
    return self.lookup_transform_core(target_frame, source_frame, time)
tf2.LookupException: "map" passed to lookupTransform argument source_frame does not exist. 
Exception in thread /tf:
Traceback (most recent call last):
  File "/usr/lib/python2.7/threading.py", line 801, in __bootstrap_inner
    self.run()
  File "/usr/lib/python2.7/threading.py", line 754, in run
    self.__target(*self.__args, **self.__kwargs)
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/tcpros_pubsub.py", line 185, in robust_connect_subscriber
    conn.receive_loop(receive_cb)
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/tcpros_base.py", line 846, in receive_loop
    self.close()
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/tcpros_base.py", line 858, in close
    self.socket.close()
AttributeError: 'NoneType' object has no attribute 'close'

I have no clue why this is happening. I have tried other transformations like from "odom" to "base_scan" and the code worked completely fine.

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by distro
close date 2022-08-06 19:11:42.906472

2 Answers

Sort by ยป oldest newest most voted
1

answered 2022-05-05 02:30:17 -0500

Joe28965 gravatar image

updated 2022-05-05 02:42:12 -0500

It might be because you haven't done a spin() anywhere. I'm pretty sure TF needs spin() to work too.

Also, you could increase the timeout duration (rospy.Duration(0.1)) to something bigger, like 2-3 seconds (rospy.Duration(3.0).

EDIT:

Have you looked at this tutorial? It tries to basically do the same as you're doing.

edit flag offensive delete link more

Comments

@Joe28965 I checked it and it didnt help me, I'm already doing what they are doing, and they didnt use rospy.spin()

distro gravatar image distro  ( 2022-05-05 13:13:56 -0500 )edit

@gvdhoorn could you please edit my code so you I can better understand what you mean? I don't know what exactly you want me to change

distro gravatar image distro  ( 2022-05-05 13:33:26 -0500 )edit

@distro Please edit your question to include your new understanding based on the information provided and ask any additional clarifications based on that instead of just expecting people here to guess about what you don't understand.

tfoote gravatar image tfoote  ( 2022-05-05 14:10:53 -0500 )edit

@tfoote I havent gained any new understanding. I looked at the link that joe28965 suggested I look at and it looked exactly like what I was doing,they also didnt use rospy.spin(). as for gvdhoorn, I still dont understand what he wants me to do exactly. If I gained any new understanding I would have said so. I seriously just havent. I will add that I have triedother transformations like from "odom" to "base_scan" and the code worked completely fine. I'll add that to my original comment.

distro gravatar image distro  ( 2022-05-05 14:41:35 -0500 )edit

Your code does not look like the tutorial that Joe linked to. gvdhoorn pointed out that you are creating the buffer and then querying it immediately which is not going to work. Your Bufferand Listener need to be persistent to be able to build up the cache and contain useful data.

tfoote gravatar image tfoote  ( 2022-05-05 17:34:32 -0500 )edit

@tfoote the code works after I tweak the duration time to be longer, I have no clue why because other transforms dont need that long a duration time, only when Im specifcally transforming from map to another frame do I need to do this. The link follows the general idea of what I was doing, they just have other stuff like the turtlesim thingy. Anyways thanks.

distro gravatar image distro  ( 2022-05-05 18:05:38 -0500 )edit

I was wrong about it needing spin()

gvdhoorn was commenting on this part of your code:

tf_buffer = tf2_ros.Buffer(rospy.Duration(tf_cache_duration))
tf2_ros.TransformListener(tf_buffer)

# get the tf at first available time
#try:
transformation = tf_buffer.lookup_transform(target_frame,source_frame, rospy.Time(0), rospy.Duration(0.1))

Here you create the tf_buffer and TransformListener and immediately try and use them to get a transform.

Those two need time to, well, buffer. The duration time is a timeout time. So you are saying that you want it to look for 3 seconds or throw an exception if it can't find one (tf2.LookupException: "map" passed to lookupTransform argument source_frame does not exist.).

Basically by changing the duration to 3 seconds, you're giving the tf_buffer and TransformListener 3 seconds to build up a cache, which is why it now works.

Joe28965 gravatar image Joe28965  ( 2022-05-06 01:17:00 -0500 )edit

@Joe28965 its all good, I found another way, I just use 'tf' instead of 'tf_ros' to transform points from one frame to another. its faster

distro gravatar image distro  ( 2022-05-06 01:51:32 -0500 )edit
2

answered 2022-05-05 04:23:46 -0500

gvdhoorn gravatar image

get_transformation(..) creates a Buffer and TransformListener and in the next line/millisecond tries to retrieve data from it.

That won't work.

edit flag offensive delete link more

Comments

Just a note for future readers: this was a comment under the (now) accepted answer. It was not meant as a full answer.

gvdhoorn gravatar image gvdhoorn  ( 2022-05-06 03:26:30 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2022-05-04 20:20:40 -0500

Seen: 2,672 times

Last updated: May 05 '22