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

data losted when subscribe from a bag file

asked 2013-03-11 02:56:38 -0500

updated 2013-03-11 03:06:31 -0500

this bag file (T_01.bag)is publishing sensor_msgs::PointCloud2 on the topic "/points". i use the following code to subscribe to that topic and save the pointcloud to disk.

#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/common/common.h>
#include <pcl/io/pcd_io.h>

int count = 0;
pcl::PCDWriter pcdWriter;

void cloudCallback(const sensor_msgs::PointCloud2ConstPtr& msg)
{
    pcl::PointCloud<pcl::PointXYZ>::Ptr pc_col(new pcl::PointCloud<pcl::PointXYZ>());
    pcl::fromROSMsg(*msg,*pc_col);
    std::cout<<"saving "<<count<<std::endl;
    std::stringstream ss;
    ss<<"point"<<count<<".pcd";
    pcdWriter.write(ss.str(),*pc_col);
    count++;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "listener");
  ros::NodeHandle n;
  ros::Subscriber sub = n.subscribe("/points", 10, cloudCallback);

  ros::spin();

  return 0;
}

The problem is, there should be 4 pointclouds in this bag file. but most of the time my program can only record 3. Could anybody figure out why?

p.s. how to make the subscriber quit automatically when the publisher is terminated?

Thanks.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2013-03-12 05:24:17 -0500

joq gravatar image

It takes time for your program to load and join the ROS message graph. Rosbag may have already published some of the messages before you are ready to receive them.

You can use rosbag play --delay=5 to delay five seconds after advertising the topic and before publishing messages. See the rosbag play documentation.

edit flag offensive delete link more

Comments

Thanks man. it works. but i'm still wondering that, do we have something like publisher.getNumSubscribers() when playing bag files such that we can judge whether or not the subscriber is ready.

yangyangcv gravatar image yangyangcv  ( 2013-03-12 14:16:48 -0500 )edit

When rosbag play starts, it tries to publish all the messages at the same time interval as when they were recorded. It is not waiting for anything. Note: there is also a rosbag play --pause option.

joq gravatar image joq  ( 2013-03-12 14:22:08 -0500 )edit

Question Tools

Stats

Asked: 2013-03-11 02:56:38 -0500

Seen: 490 times

Last updated: Mar 12 '13