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

Tried to insert a message with time less than ros::TIME_MIN Aborted (core dumped)

asked 2019-06-13 14:13:26 -0600

RayROS gravatar image

updated 2019-06-13 16:39:42 -0600

jayess gravatar image

Hello, after successfully reading .pcd file from a file as asked on my previous post I was trying to to write to a rosbag but it is not working. I wanted to check if messages are currently being received using rostopic list /echo but I am receiving a compiler error:

emanuele@Manny:~$ rosrun map_ros pointcloud_reader_node 
terminate called after throwing an instance of 'rosbag::BagException'
  what():  Tried to insert a message with time less than ros::TIME_MIN
Aborted (core dumped)

I have never received this error, and by reading official documentation and other useful sources I don't understand how this ros::TIME_MIN exception could be handled.

See below the code I am using for that:

cloud.h

class Cloud
{
public:
    void readPCloud(std::string filename, ros::NodeHandle &n);
    sensor_msgs::PointCloud2 pCloud2Msg;

    ros::Subscriber cloud_sub;
    ros::Publisher cloud_pub;
    ros::Timer particleTimer;
    ros::NodeHandle _n;

private:

    void timerCallback(const ros::TimerEvent&)
    {
        publishPointCloud();
    }

    void publishPointCloud()
    {
        sensor_msgs::PointCloud2 particleCloudMsg;
        particleCloudMsg.header.stamp = ros::Time::now();
        particleCloudMsg.header.frame_id = "cloud";
        cloud_pub.publish(particleCloudMsg);
    }
};

cloud.cpp

void Cloud::readPCloud(std::string filename, ros::NodeHandle &n)
{
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
    if(pcl::io::loadPCDFile<pcl::PointXYZ> (filename, *cloud) == -1) // load point cloud file
    {
        PCL_ERROR("Could not read the file");
        return;
    }
    std::cout<<"Loaded"<<cloud->width * cloud->height
             <<"data points from /home/to/Desktop/cloud_25.pcd "
             <<std::endl;
    for(size_t i = 0; i < cloud->points.size(); ++i)
        std::cout << "    " << cloud->points[i].x
                  << " "    << cloud->points[i].y
                  << " "    << cloud->points[i].z << std::endl;

    particleTimer = n.createTimer(ros::Duration(1), &Cloud::timerCallback, this);
}

pointcloud_reader_node.cpp

int main(int argc, char** argv)
{
    ros::init (argc, argv, "pcl_tutorial_cloud");
    ros::NodeHandle nh;
    ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("output", 1000);
    ros::Rate loop_rate(1);
    rosbag::Bag bag;
    bag.open("cloud.bag", rosbag::bagmode::Write);
    std::string fstring = "/home/to/Desktop/cloud_25.pcd";
    Cloud p;
    int count = 0;
    while(ros::ok())
    {
        sensor_msgs::PointCloud2 pcloud2;
        pub.publish(pcloud2);
        bag.write("cloud/data", p.pCloud2Msg.header.stamp , p.pCloud2Msg);
        ros::spinOnce();
        loop_rate.sleep();
        count ++;
    }
    return 0;
}

Thanks for shedding light on this issues

edit retag flag offensive close merge delete

Comments

Hi ,have you figured it out?

LongruiDong gravatar image LongruiDong  ( 2019-12-04 22:41:31 -0600 )edit

Hi LongruiDong, I have not unfortunately. So this post is still open for possible solutions if someone found it. I took another way back then.

RayROS gravatar image RayROS  ( 2019-12-16 11:28:03 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-03-19 13:20:47 -0600

Gaborka gravatar image

Even though ros::Time is initialized to 0 seconds 0 nanoseconds (like it is by default in your code), you cannot add a message to a bag file with this timestamp. It has to be at least 0 seconds and 1 nanosecond. Generally, you should make sure that the timestamp you are about to pass in is not 0:

ros::Time timeStamp;
//...
if (timeStamp.toNSec == 0) timeStamp = ros::TIME_MIN;
bag.write("topic", timeStamp, message);

I just checked, ros::TIME_MIN will set the bag time to exactly 0 seconds and 1 nanosecond.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2019-06-13 14:13:26 -0600

Seen: 1,667 times

Last updated: Mar 19 '20