Perform long computation in callback

asked 2018-10-09 11:54:47 -0500

Alonso Martinez gravatar image

I would like to know which approach is recommended between:

  1. doing a long computation in the callback with a queue size of 1
  2. copying the data with some mutex and doing the computation in the spin

Losing frames are ok but I need to process always the last frame, hence a queue size of 1.

For 2, something like:

class Processing {
  ros::NodeHandle m_nh;
  unsigned int m_queue_size;
  message_filters::Subscriber<sensor_msgs::Image> m_image_color_sub;
  message_filters::Subscriber<sensor_msgs::CameraInfo> m_cam_info_sub;
  typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::CameraInfo> MySyncPolicy;
  message_filters::Synchronizer<MySyncPolicy> m_sync;
  bool m_receive_new_image;
  boost::mutex m_lock_new_image;
  sensor_msgs::ImageConstPtr m_new_image_color;
  sensor_msgs::CameraInfoConstPtr m_new_cam_info;

public:
  Processing() :
      m_nh(),m_queue_size(1),
      m_image_color_sub(m_nh, "/camera/image", m_queue_size), m_cam_info_sub(m_nh, "/camera/camera_info", m_queue_size),
     m_sync(MySyncPolicy(10), m_image_color_sub, m_cam_info_sub),
     m_receive_new_image(false), m_lock_new_image(), m_new_image_color(),
     m_new_cam_info() {
     m_sync.registerCallback(boost::bind(&Processing::callback, this, _1, _2));
  }

  void spin() {
    ros::Rate loop_rate(120);

    while (m_nh.ok()) {
      process();

      ros::spinOnce();
      loop_rate.sleep();
    }
  }

  void callback(const sensor_msgs::ImageConstPtr& msg_color, const sensor_msgs::CameraInfoConstPtr& msg_cam_info     ) {
      boost::mutex::scoped_lock(m_lock_new_image);
      m_receive_new_image = true;
      m_new_image_color = msg_color;
      m_new_cam_info = msg_cam_info;
  }

  void process() {
    try {
      {
        boost::mutex::scoped_lock(m_lock_new_image);
        if (m_receive_new_image) {
          m_receive_new_image = false;
          //Convert data to correct format and release the mutex
        } else {
          return;
        }
      }

      //Long computation time
    } catch (const cv_bridge::Exception& e) {
      ROS_ERROR("cv_bridge exception: %s", e.what());
    }
  }
};
}

int main(int argc, char** argv) {
  ros::init(argc, argv, "processing_node");
  Processing processing;
  processing.spin();

  return 0;
}

For 1, the same thing but with:

  void spin() {
    ros::Rate loop_rate(120);

    while (m_nh.ok()) {    
      ros::spinOnce();
      loop_rate.sleep();
    }
  }

And the long computation time directly in the callback.

The input images will be received at a higher rate than the processing function will be able to process.

Also, in 2 is there a need to use mutex since the callback is called with ros::spinOnce() and so there is no risk of data races?

edit retag flag offensive close merge delete

Comments

More or less the right track. You need to probably do something with your mutex in the callback so that it tries to get the mutex but if it fails it just passes because something if using it being processed. Otherwise the callback will block for the mutex.

stevemacenski gravatar image stevemacenski  ( 2018-10-09 13:12:02 -0500 )edit

I thought that the callback is called only with ros::spinOnce()? This is how understand this answer.

For me, there is no concurrency between the callback and the process function.

Alonso Martinez gravatar image Alonso Martinez  ( 2018-10-09 15:18:12 -0500 )edit

@Alonso Martinez, you're correct. Your node is using ros::spinOnce() therefore it's single threaded and you don't really need to use mutex for data protection. The problem here is that your callback function has different rate than your process function. Therefore if you use single threade

l4ncelot gravatar image l4ncelot  ( 2018-10-10 09:17:02 -0500 )edit

... node your main loop will wait and do nothing while you process the last image (which would be already old at that point because new images arrive with greater speed). This could be solved using multi threaded approach with AsyncSpinner where you'll have to use mutex to protect data.

l4ncelot gravatar image l4ncelot  ( 2018-10-10 09:20:26 -0500 )edit

@l4ncelot

I understand that multi-threaded approach would be better.

If images come at 30 Hz but I can only process at 10 Hz, with a queue size of 1, the process that handles messages does not overwrite the buffer in a way that I will get a close to recent image?

Alonso Martinez gravatar image Alonso Martinez  ( 2018-10-10 10:06:25 -0500 )edit

@Alonso Martinez I think it depends on the buffer queue size you set in your publisher. It will not overwrite messages until the buffer queue size exceeds. Then it will just erase the old ones, which is alright.

l4ncelot gravatar image l4ncelot  ( 2018-10-11 01:42:03 -0500 )edit