0
$\begingroup$

Rosanswers logo

Hello,

I am very new to ROS and I have just manged to integrate the ROS libraries into my QT IDE.

I am building a fairly complex application, however the ROS subscriber example I am attempting to implement fairly simple.

If I implement my code this way (per the examples), I get subscriber callbacks as expected:

void MainWindow::rtsp1Callback(const sensor_msgs::Image::ConstPtr& msg)
{
    qDebug() << "rtsp1 Image has data";
}

With this initializer:

void MainWindow::on_ROSSubscribeButton_clicked()
{
    ros::init(m_argc, m_argv, "camera_check");
    ros::NodeHandle n1;
    ros::Subscriber sub1 = n1.subscribe("/rtsp_1/image_raw", 100, &MainWindow::rtsp1Callback, this);
    ros::spin();
}

But of course, this is an undesirable design, as ros::spin(); then blocks the rest of my program.

So I execute a timer to call ros::spinOnce(); on demand:

Callback unchanged:

void MainWindow::rtsp1Callback(const sensor_msgs::Image::ConstPtr& msg)
{
    qDebug() << "rtsp1 Image has data";
}

Initializer with timer:

void MainWindow::on_ROSSubscribeButton_clicked()
{
    ros::init(m_argc, m_argv, "camera_check");
    ros::NodeHandle n1;
    ros::Subscriber sub1 = n1.subscribe("/rtsp_1/image_raw", 100, &MainWindow::rtsp1Callback, this);
    CameraCheckTimer.start(100);  //calls ros::spinOnce() every 1000ms;
}

And this spin call (on timer execution):

void MainWindow::checkCameras()
{
    ros::spinOnce();
    qDebug() << "Spin!";
}

However I do not get any callbacks.

I also tested calling ros::spin() - which was working in my initial example, by calling a singleShot timer. When I do this, my program blocks as expected, however I do not get any callbacks.

This makes me suspect that ros::spin() and ros::spinOnce() are somehow getting an implicit pointer to the GlobalCallbackQueue from the ros::init() function. Is this the case?

If so, what is the data type of ros::GlobalCallbackQueue (so that I can pass a global pointer to it into my timer loop)?

Or, if you have an example of how to simply fix my problem, I will accept that as well!


Originally posted by riot on ROS Answers with karma: 28 on 2019-07-12

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Initializer with timer:

void MainWindow::on_ROSSubscribeButton_clicked()
{
    ros::init(m_argc, m_argv, "camera_check");
    ros::NodeHandle n1;
    ros::Subscriber sub1 = n1.subscribe("/rtsp_1/image_raw", 100, &MainWindow::rtsp1Callback, this);
    CameraCheckTimer.start(100);  //calls ros::spinOnce() every 1000ms;
}

However I do not get any callbacks.

The problem here is scope: sub1 goes out of scope as soon as on_ROSSubscribeButton_clicked() completes.

So the Subscriber gets destroyed, cancelling the subscription. Additionally, the NodeHandle also vanishes.

Caling ros::spinOne() at this point doesn't really do much any more, as there are no subscriptions.

Make sure to keep the ros::Subscriber around, and probably also the ros::NodeHandle (as a member variable fi). Things should start working.

This makes me suspect that ros::spin() and ros::spinOnce() are somehow getting an implicit pointer to the GlobalCallbackQueue from the ros::init() function. Is this the case?

If so, what is the data type of ros::GlobalCallbackQueue (so that I can pass a global pointer to it into my timer loop)?

I don't believe this has anything to do with your problem.


Originally posted by gvdhoorn with karma: 86574 on 2019-07-12

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by riot on 2019-07-12:
Thank you for your very concise answer!

I simply declared the handles as 'static' and they now persist outside of the creation function:

void MainWindow::on_ROSSubscribeButton_clicked()
{
    ros::init(m_argc, m_argv, "camera_check");
    static ros::NodeHandle n1;
    static ros::Subscriber sub1 = n1.subscribe("/rtsp_1/image_raw", 100, &MainWindow::rtsp1Callback, this);
    CameraCheckTimer.start(100);  //calls ros::spinOnce() every 1000ms;
}

I get the callbacks as expected.

Comment by gvdhoorn on 2019-07-12:
I wouldn't declare them static, but if you are ok with doing it that way, that would work.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.