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

Bug or intended behaviour: TransformListener::waitForTransform does not poll ros::ok()

asked 2014-07-03 07:11:46 -0500

Wolf gravatar image

Hi there,

I wondered why my one of my nodes did not terminate on SIGINT Crtl+C when /use_sim_time is true and tracked it down to a call of TransformListener::waitForTransform. In the waiting loop of this function, which calls Buffer::canTransform, no polling of ros::ok() is involved.

The respective loop is (see https://github.com/tulku/tf2_ros/blob... ):

  while (now_fallback_to_wall() < start_time + timeout &&
!canTransform(target_frame, source_frame, time) &&
         now_fallback_to_wall() >= start_time) //don't wait if time jumped backwards
    ros::Duration(0.01).sleep();

Omitting the poll of ros::ok() here causes the following behaviour after a SIGINT:

  • If /use_sim_time is false, the function call still blocks the entire given duration if a SIGINT happens during the waiting duration and does not immediately return false (the result won't change, though, because after the SIGINT subscriber callbacks are no longer called....)
  • If /use_sim_time is true, the function blocks forever after a SIGINT because the clock subscriber is not called anymore and the end of the timeout will never be reached.....

The following snippet is a minimal example which has this behaviour an my machine (ubuntu 12.04 64Bit + ROS Hydro)

#include <ros/ros.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>

int main ( int argc, char** argv )
{
  ros::init( argc, argv, "tf_test" );

  ros::NodeHandle lo_nh;

  tf::TransformListener lo_listener;

  // only to get sim time and tf listener in sync before waiting
  ros::spinOnce();
  ros::Duration(1).sleep();
  ros::spinOnce();
  ros::Duration(1).sleep();
  ros::spinOnce();
  ros::Duration(1).sleep();
  ros::spinOnce();

  ROS_INFO( "init" );

  ros::Time lo_t1 = ros::Time::now();
  ros::Time lo_t2 = lo_t1 - ros::Duration( 1.0 );

  // returns true if tf is broadcasted in sync with time
  // returns false after 10 sec if no tf and no SIGINT
  // returns false after 10 sec if no tf and SIGINT and /use_sim_time false
  // blocks forever if no tf and SIGINT and /use_sim_time true
  if ( lo_listener.waitForTransform("/base_footprint", lo_t1, "/base_footprint", lo_t2, "/odom", ros::Duration( 10 ) ) )
  {
    ROS_INFO( "tf available" );
  }
  else
  {
    ROS_INFO( "tf not available" );
  }

  ROS_INFO( "spin" );

  ros::spin();

  return 0;
}

Is this intended/accepted or should a ros::ok() be included in the loop condition??

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2014-07-03 08:46:46 -0500

jbohren gravatar image

This is a bug, thank you for bringing more attention to it!

It's currently being tracked on github here: https://github.com/ros/geometry_exper...

Could you add this additional information, or better yet, a pull request adding the call to ros::ok()?

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-07-03 07:11:46 -0500

Seen: 675 times

Last updated: Jul 03 '14