새소식

ROS & Robotics

ROS message filter: waitForTransform() Lookup error

  • -

이전 포스팅:

이와 같이 bounding_boxes 토픽의 time stamp 를 수정해 주고 난 후 또 에러를 마주쳤습니다.

Transform error: Lookup would require extrapolation into the future. Requested time 1401446451.006236446 but the latest data is at time 1401446450.937553891, when looking up transform from frame [base_scan] to frame [camera]
[ERROR] [1401446451.007936297]:

waitForTransform() 에서 요구하는 데이터는 A 시점의 데이터인데, 가장 최근에 들어오는 데이터는 B 시점의 데이터라는 뜻입니다.

문제점

rosbag 데이터를 이용해 실험을 진행하고 있기 때문에 센서 데이터 획득 시점과 데이터를 재생하는 시점이 다르다.

해결책

해결 방법 : use_sim_time 을 true 로 설정하고 , clock 을 직접 발행한다.

  1. 우선 bag 플레이 옵션 중 use_sim_time 을 true 로 설정해 줍니다.
<param name="/use_sim_time" value="true"> //launch 파일을 사용하는 경우

rosparam set use_sim_time true //command line 을 사용하는 경우

use_sim_time : 전역 시간을 사용하지 않고, rosbag play —clock 데이터이름.bag 옵션을 주었을 때 발행되는 /clock 토픽을 기준으로 삼겠다.

저는 /clock 토픽의 시간이 /scan 토픽의 time stamp 와 정확히 같기를 원하기 때문에 이런 기능을 하는 패키지를 새로 만들어 줍니다.

Time(0): tf cache 의 첫 번째 tf 정보
now() : 현재 시간의 tf 정보

re_time_stamp 패키지

#include <ros/ros.h>
#include <std_msgs/Time.h>
#include "rosgraph_msgs/Clock.h"
#include <sensor_msgs/LaserScan.h>
#include <time.h>

class SubscribeAndPublish
{
public:
  SubscribeAndPublish()
  {
    pub_ = n_.advertise<rosgraph_msgs::Clock>("/clock", 10); //clock 토픽 발행
    sub_ = n_.subscribe("/scan", 10, &SubscribeAndPublish::callback, this); //scan 포틱 구독
  }

  void callback(const sensor_msgs::LaserScan& input)
  {
    std_msgs::Time time;
    time.data = input.header.stamp; //scan 토픽에서 헤더를 가져와 time.data 에 넣어 줍니다. 
    pub_.publish(time);
  }

private: 
  ros::NodeHandle n_; 
  ros::Publisher pub_;
  ros::Subscriber sub_;
};

int main(int argc, char **argv)
{
  ros::init(argc, argv, "re_time_stamp");
  SubscribeAndPublish SAPObject; 
  ros::spin();
  return 0;
}

이렇게 되면 /clock 과 /scan 의 time stamp 가 동일하게 발행되는 것을 볼 수 있습니다.

이 패키지를 실행하면 전역 시간이 rosbag record 를 시행한 시점이 됩니다.

Contents

포스팅 주소를 복사했습니다

이 글이 도움이 되었다면 공감 부탁드립니다.