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

detecting timeout from waitForMessage

asked 2013-08-15 23:07:13 -0600

wesleyc gravatar image

updated 2013-08-20 14:35:15 -0600

Hi,

I'm using the waitForMessage function and can't seem to be able to find a way of detecting if the function has timed out.

Here's the code I have:

sensor_msgs::PointCloud2 pc;
pc  = *(ros::topic::waitForMessage<sensor_msgs::PointCloud2>(rgb_topic_, ros::Duration(10)));

How can I check and see if pc is valid?

If I try to read the fields of pc when it has timed out, the code exits with the following error:

calibration_executive: /usr/include/boost/smart_ptr/shared_ptr.hpp:412: boost::shared_ptr<T>::reference boost::shared_ptr<T>::operator*() const [with T = const sensor_msgs::PointCloud2_<std::allocator<void> >, boost::shared_ptr<T>::reference = const sensor_msgs::PointCloud2_<std::allocator<void> >&]: Assertion `px != 0' failed.
Aborted

By the way, the code is from the pr2_led_kinect_calib package.

Thanks.

------------------- update ------------------

Tried putting it in a try catch block but it didn't work

    try
    {
        pc  = *(ros::topic::waitForMessage<sensor_msgs::PointCloud2>(rgb_topic_, ros::Duration(10)));
        if ((after == ros::Time(0,0)) || (pc.header.stamp > after))
        {
            found = true;
        }   

    }
    catch (std::exception e)
    {
        ROS_ERROR("No point clound messages received in topic %s after waiting for %f seconds.", rgb_topic_.c_str(), waitTime);
        continue;
    }

It aborts at

    if ((after == ros::Time(0,0)) || (pc.header.stamp > after))

and no exception is thrown.

Also tried

if (!pc)

But pc is not a pointer so it gives a type mismatch compilation error.

------------------- update ------------------

Thanks for the responses!

As suggested, I tried storing the returned value as a shared pointer, then checking to see if it's NULL, and that worked.

boost::shared_ptr<sensor_msgs::PointCloud2 const> sharedPtr;
sensor_msgs::PointCloud2 pc;

sharedPtr  = ros::topic::waitForMessage<sensor_msgs::PointCloud2>(rgb_topic_, ros::Duration(10));
    if (sharedPtr == NULL)
        ROS_INFO("No point clound messages received);
    else
        pc = *sharedPtr;
edit retag flag offensive close merge delete

Comments

What if you define pc as a pointer (PointCloud2Ptr pc) and then check if it points to zero?

timster gravatar image timster  ( 2013-08-16 02:02:44 -0600 )edit

This will also work:

sensor_msgs::PointCloud2 pc;
sensor_msgs::PointCloud2ConstPtr msg = ros::topic::waitForMessage<sensor_msgs::PointCloud2>(rgb_topic_, ros::Duration(10));
    if (msg == NULL)
        ROS_INFO("No point clound messages received);
    else
        pc = * msg;
sven-cremer gravatar image sven-cremer  ( 2015-01-02 14:22:03 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2013-08-16 03:55:14 -0600

dornhege gravatar image

updated 2013-08-16 03:55:26 -0600

I'd image the best way is to NOT assign the pointcloud, but use a shared pointer.

If the functions times out that shared pointer should be empty. You also see the sensor_msgs::PointCloud2_<std::allocator<void> >&]: Assertion px != 0' failed. pop up. You can check that before.

edit flag offensive delete link more
0

answered 2013-08-16 00:27:40 -0600

timster gravatar image

I use a try-catch block for tf::TransformListener::waitForTransform. In your case, I would try something like:

sensor_msgs::PointCloud2 pc;
try
{
    pc  = *(ros::topic::waitForMessage<sensor_msgs::PointCloud2>(rgb_topic_,ros::Duration(10)));
}
catch()
{
    ROS_WARN("something");
}
edit flag offensive delete link more

Comments

Unfortunately I've tried that and it didn't work. The call to waitForMessage returns normally. But after that when the next line does if ((after == ros::Time(0,0)) || (pc.header.stamp > after)) it causes the program to abort. No exception is being thrown by waitForMessage or pc.header.stamp.

wesleyc gravatar image wesleyc  ( 2013-08-16 01:26:15 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2013-08-15 23:07:13 -0600

Seen: 12,587 times

Last updated: Aug 20 '13