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

How to verify publications using rostest?

asked 2014-10-15 12:51:31 -0500

kyrofa gravatar image

I have several pieces of software in ROS, all of which are pretty thoroughly unit and integration tested. However, there's one aspect of testing within ROS that I have yet to accomplish with much success: Verifying publications.

Note that I'm still stuck in the dark ages of Fuerte, but I believe my question is relevant to more recent releases as well.

I currently have several tests within rostest, which looks like this in my CMakeLists.txt:

rosbuild_add_executable(my_tests EXCLUDE_FROM_ALL ${MY_TESTS})
rosbuild_add_gtest_build_flags(my_tests)
rosbuild_add_rostest(${PROJECT_SOURCE_DIR}/test/node/node.test)

Running this with make test also runs a roscore (since node.test is a launch file), so these tests can make use of classes that require a connection to roscore. I'd like to use this to verify publications, but it's not working reliably, which makes me think I'm doing something wrong. As an example:

class TestSubscriber
{
    public:
        TestSubscriber() : receivedMessage(false) {}

        void callback(const std_msgs::Int32ConstPtr &newMessage)
        {
            receivedMessage = true;
            message = newMessage;
        }

        bool receivedMessage;
        std_msgs::Int32ConstPtr message;
}

TEST(MyTest, TestPublication)
{
    // This class will publish on the "output" topic. It will create a node handle
    // and advertise in its constructor.
    MyPublishingClass publishingClass;

    ros::NodeHandle nodeHandle;

    TestSubscriber subscriber;
    ros::Subscriber rosSubscriber = nodeHandle.subscribe("output",
                                                         1,
                                                         &TestSubscriber::callback,
                                                         &subscriber);
    ASSERT_EQ(1, rosSubscriber.getNumPublishers()); // This passes

    publishingClass.publishMessage();

    ros::spinOnce(); // Spin so that publication can get to subscription

    EXPECT_TRUE(subscriber.receivedMessage); // This may or may not be true
}

Depending on how the MyPublishingClass is written, this test may pass or fail due to that last line. To give a specific example, I have a class that reads through a bagfile and publishes specific topics. If that class publishes topics with:

publisher.publish(rosBagViewIterator->instantiate<std_msgs::Int32>());

the test passes. If instead the class publishes with:

publisher.publish(*rosBagViewIterator);

the test fails (even though the node still runs normally outside of the test, so I know that publication is actually happening). I have more examples of similar weirdness, but I'm hoping this is enough to describe my problem.

So, down to my questions:

  1. Why is this so finicky? I realize that it's basically a node subscribing to its own publication, but that shouldn't be a problem. Should it?
  2. Am I doing this wrong? Is there a better way to test ROS publications? Note that the class in question is not a complete ROS node, and cannot be tested as such.
edit retag flag offensive close merge delete

Comments

Thanks for the link Dirk! That is indeed exactly what I'm doing-- hopefully I'll be able to narrow it down a bit more.

kyrofa gravatar image kyrofa  ( 2014-10-16 11:06:42 -0500 )edit

Hi Kyle, did you manage to find out why the callback was inconsistent? I am having exactly the same problem. Let me know if you found something

DavidN gravatar image DavidN  ( 2016-09-12 04:32:19 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
3

answered 2014-10-15 15:31:27 -0500

Dirk Thomas gravatar image

There is a unit test covering exactly your use case ( https://github.com/ros/ros_comm/blob/... ) which reliably passes. So I guess it must be something in your code - may be in the parts not posted here.

edit flag offensive delete link more
1

answered 2020-03-18 14:30:06 -0500

peci1 gravatar image

updated 2020-03-18 14:36:01 -0500

For more complicated cases, here's what I use:

sensor_msgs::PointCloud2ConstPtr pcl;
auto sub = nh.subscribe<sensor_msgs::PointCloud2>("scan", 10, [&](const sensor_msgs::PointCloud2ConstPtr& msg){pcl=msg;});

// publish

#define WAIT_FOR_MESSAGE(msg) \
{ size_t i = 0;\
  while (ros::ok() && msg == nullptr && i < 100) \
  { \
    ros::spinOnce(); \
    ros::WallDuration(0.01).sleep(); \
    ++i;\
  } \
  if (i == 100) ADD_FAILURE(); \
}

WAIT_FOR_MESSAGE(pcl)
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-10-15 12:50:47 -0500

Seen: 6,165 times

Last updated: Mar 18 '20