Error: TF_SELF_TRANSFORM

Example

  •  TF_SELF_TRANSFORM: Ignoring transform from authority "default_authority" with parent_id and frame_id  "/same_frame" because they are the same

Solution:

  • TF_SELF_TRANSFORM errors occur when a transform is published with itself listed as its parent. TF will ignore this information for it is impossible to be your own parent. This means that there is a problem with the source of that transform which is listed as the authority in the error message.

Error: TF_OLD_DATA

Example:

  •  TF_OLD_DATA ignoring data from the past for frame left_gripper at time 1415804777

Solution:

  • TF_OLD_DATA errors mean that a transform is attempted to be added to the system, but the data is greater than cache_time_ before the most recent data received for this link.
  • The most common cause of TF_OLD_DATA warnings are if rostime has gone backwards. This can be caused by restarting a bag playback or restarting a simulator. The fix for this is to send an Empty message the topic /reset_time. There is a button in rviz to do this.
  • Another possible source of TF_OLD_DATA is if there is any outdated or delayed source of transforms. The error message will tell you which authority is sending the outdated data. If it is running in a ros node you can use view_frames to determine the more recent authority. See view_frames.

Error: TF_NO_FRAME_ID

Example:

  •  TF_NO_FRAME_ID: Ignoring transform from authority "default_authority" because frame_id not set

Solution:

  • The TF_NO_FRAME_ID error means that a transform was attempted to be set with an empty frame_id. This transform will be ignored by TF.

Error: TF_NO_PARENT_ID

Example:

  • TF_NO_PARENT_ID: Ignoring transform with frame_id "/my_frame"  from authority "default_authority" because parent_id not set

Solution:

  • The TF_NO_PARENT_ID error means that a transform was attempted to be set with an empty parent_id. This transform will be ignored by TF.

Error: TF_NAN_INPUT

Example:

  •  TF_NAN_INPUT: Ignoring transform for frame_id "/same_frame" from authority "default_authority" because of a nan value in the transform (1.000000 1.000000 nan) (0.000000 0.000000 0.000000 1.000000)

Solution:

  • The TF_NAN_INPUT error means that a transform was attempted to be set with a nan value. This transform will be ignored by TF.

Error: ExtrapolationExceptions

Example:

  • Lookup would require extrapolation into the future.  Requested time 273.121000000 but the latest data is at time 273.100000000, when looking up transform from frame [base_footprint] to frame [map]

Solution:

A constant offset extrapolation error is often caused by a lack of synchronization of the clocks between computers. One computer thinks it is ahead of the other and consequently the data received on a different machine will be off consistently. As new data comes in, the closest data will always be the same distance away resulting in the constant ExtrapolationException.

  • I'm seeing a very small extrapolation in the future. Where might that come from?

In a distributed system information is not available instantaneously in all parts of the system. Depending on the setup, it is possible for data to be available before all the transforms necessary are available. The recommended way to deal with this is to use a tf::MessageFilter.

  • I'm seeing a huge (~1.2E9 second) extrapolation error, why is that?

Most likely this is a problem that part of the ROS system is running on sim time, while part is running without sim time. Make sure that all nodes are started while time is being published. And set the param "/use_sim_time" to true so that on startup there will not be a race condition for what mode ros::Time is running in.

Error: LookupException

Example:

  •  FILLME

Solution:

A LookupException is thrown in the case that a frame id requested does not exist in the tf tree.

  • What does "Recursed too deep into graph" mean?

This error is thrown when tf finds itself taking more than MAX_GRAPH_DEPTH steps to try to find the top of the tree. This is set high enough that the only common reason to hit this point is if the graph has a cycle in it. Look at the rest of the error message and see if any cycles exist. The program tf_monitor will show who is publishing which transform.

Error: ConnectivityException

Example:

  •  FILLME

Solution:

  • What does a connectivityException tell me about my robot?

A ConnectivityException says that it is not possible to transform between the requested frame_ids.

The most common source of a ConnectivityException is that a tf authority is not publishing an intermediate transform required to get between the source and target frame. If you are running a large launch script look carefully for any nodes crashing or failing to start. The best utility to see what is being published is view_frames see view_frames for usage.

  • What do the different versions of ConnectivityExceptions mean?

    • NO_PARENT at top of tree means that one or both of the target and source frame ids has NO_PARENT set as it's parent_id.
    • No Common Parent Case A is when the forward transform list is zero length and the top of the inverse transform list is not the target frame_id.
    • No Common Parent Case B is when the forward and inverse transform lists are both zero length, but the target and source frame_ids are not the same.
    • No Common Parent Case C is when the end of the forward transform list is not equal to the source_frame, but the inverse list is zero length.
    • No Common Parent Case D is the same as B.
    • What does "Could not find a common time" mean?

This will be thrown when using getLatestCommonTime (usually done by passing a time of 0 to the tf API) if the frames exist and are connected but there are no overlapping data in time. Often this is caused by one or more frames stopping being published.

Wiki: tf/Errors explained (last edited 2021-04-22 08:06:53 by KosmasTsiakas)