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

Lookup would require extrapolation into the past

asked 2016-07-11 07:20:41 -0500

viki_rover gravatar image

updated 2016-07-11 08:38:44 -0500

Good afternoon,

I have a problem when converting a laser scan into a point cloud map using ros indigo virtual machine. I get the following error :

terminate called after throwing an instance of 'tf2::ExtrapolationException' what(): Lookup would require extrapolation into the past. Requested time 1467669390.062319560 but the earliest data is at time 1467669390.111446506, when looking up transform from frame [LIDAR] to frame [base_link] Aborted (core dumped)

After running this code:

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


class My_Filter {
     public:
        My_Filter();
        void scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan);
     private:
        ros::NodeHandle node_;
        laser_geometry::LaserProjection projector_;
        tf::TransformListener tfListener_;

        ros::Publisher point_cloud_publisher_;
        ros::Subscriber scan_sub_;
};

My_Filter::My_Filter(){
        scan_sub_ = node_.subscribe<sensor_msgs::LaserScan> ("/scan", 100, &My_Filter::scanCallback, this);
        point_cloud_publisher_ = node_.advertise<sensor_msgs::PointCloud2> ("/cloud", 100, false);
        tfListener_.setExtrapolationLimit(ros::Duration(10.0));
}

void My_Filter::scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan){
    sensor_msgs::PointCloud2 cloud;
    projector_.transformLaserScanToPointCloud("base_link", *scan, cloud, tfListener_);
    point_cloud_publisher_.publish(cloud);
}

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

    My_Filter filter;

    ros::spin();

    return 0;
}

Thank you for your help

edit retag flag offensive close merge delete

Comments

I ended up in this thread looking for a solution for this problem. But my issue was that I assigned a time to stamp pc.header.stamp = ros::Time::now(); instead of separating accordingly in sec and nsec

ignacio gravatar image ignacio  ( 2021-06-17 09:17:18 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-07-11 08:45:22 -0500

updated 2016-07-11 08:49:12 -0500

You are trying to transform the laser scan to base_link before you have the required tf information. You can solve this by either

The message filter is the most idiomatic. Otherwise I'd recommend waitForTransform with a timeout.

edit flag offensive delete link more

Comments

Thank you for your answer it worked !

viki_rover gravatar image viki_rover  ( 2016-07-14 05:48:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-07-11 07:20:41 -0500

Seen: 5,643 times

Last updated: Jul 11 '16