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

ROS Nodelet receive and processing in parallel

asked 2017-04-20 06:06:30 -0600

Mondi gravatar image

updated 2017-04-22 08:56:08 -0600

Hallo community,

what is the best way to provide a heavy/slow process always the newest message when the process is ready to start the work again with new data?

My scenario is the following: - long term image processing that is slower as the depth and rgb image publishing rate

So how is it now possible to provide the newest combined message ( depth and rgb image) to the processing at any time the image processing has finished the old job.

Is it necessary to write code that handle the receiving part in a own thread and share the newest combined message with the processing thread or is there already a ROS implementation which handles such problems?

Additional Question

Will it be possible to publish in the processing thread or better how is it possible to publish form the processing thread?

Everything is implemented in a nodelet class like as nlamprian suggests.

For example:

std::shared_ptr<image_transport::ImageTransport> it_;
image_transport::Publisher resultPub_;

it_.reset(new image_transport::ImageTransport(nh));
resultPub_ = it_->advertise("result_image", 1);

std::thread processingThread;
processingThread = std::thread(std::bind(&processingLoop, this));

void processingLoop() {
  while (ros::ok()) {
    std::unique_lock<std::mutex> lock(img_mutex);
    if (has_new_data.load()) {
      // do heavy processing
      resultPub_,publish(result_msg);
    }
    has_new_data.store(false);
    processing_cv.wait(lock, [&] { return has_new_data.load(); });
  }
}

Best,

Manuel

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2017-04-20 20:26:27 -0600

Geoff gravatar image

For making sure the newest message is used, you should set your topic history queues to 1. That way, every time a new message is received it will overwrite the previous one, so only the most recent is available at all times.

For synchronising the depth and rgb images, you can use the Time Synchronizer message filter. I'm not sure how this filter handles history, so you might need to experiment to make sure it only passes the most recent of both the image and depth topics.

edit flag offensive delete link more
0

answered 2017-04-21 01:48:42 -0600

First of all, you can't do the processing in the callback, because it will (potentially) block the other nodelets.

Here is what you can do:

  1. Create a Synchronizer of queue size 1.
  2. Create your own thread to do the processing. It will contain a loop and will be waiting to be notified in order to start the processing.
  3. In the callback, you should check if data are being currently processed. If yes, discrard the received data. Otherwise, store the data and notify the processing loop.

Some libraries of interest are thread, mutex, atomic, and condition variable. Here is how this could translate to code:

void processingLoop() {
  while (ros::ok()) {
    std::unique_lock<std::mutex> lock(img_mutex);
    if (has_new_data.load()) {
      // do heavy processing
    }
    has_new_data.store(false);
    processing_cv.wait(lock, [&] { return has_new_data.load(); });
  }
}

void callback(const RgbConstPtr& rgb, const DepthConstPtr& depth) {
  std::unique_lock<std::mutex> lock(img_mutex, std::try_to_lock);
  if (!lock.owns_lock()) return;

  img_rgb = rgb;
  img_depth = depth;
  has_new_data.store(true);

  lock.unlock();
  processing_cv.notify_one();
}
edit flag offensive delete link more

Comments

Thank you, that is exactly what I've been looking for.

Perhaps you can also answer my addition.

Mondi gravatar image Mondi  ( 2017-04-22 08:59:44 -0600 )edit

Given that everything is inside the nodelet class (and so the publisher is a member variable), there isn't much to consider. Just call publish from within your processing method.

nlamprian gravatar image nlamprian  ( 2017-04-22 15:45:22 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2017-04-20 06:06:30 -0600

Seen: 684 times

Last updated: Apr 22 '17