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

how to write a thread in ROS

asked 2015-09-21 08:59:43 -0500

elthef gravatar image

I would like to know how to write a async thread in ROS. An example would be greatly appreciated. Edwin

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2015-09-21 16:10:43 -0500

updated 2015-09-21 17:03:57 -0500

Assuming you are looking for C++ solution, here is what the Wiki page on Callbacks and Spinning says:

roscpp does not try to specify a threading model for your application. This means that while roscpp may use threads behind the scenes to do network management, scheduling etc., it will never expose its threads to your application. roscpp does, however, allow your callbacks to be called from any number of threads if that's what you want.

Please also see this question with answers.

In short: you can choose any threading library you like; ROS nodes and callbacks are thread-safe. However, to avoid extra dependencies it is a good idea to use Boost threads (ROS utilises Boost for many internal components).

Here are the docs and examples for Boost threads. Also, if c++11 compiler is available then you can try std::thread. Or you even can use POSIX Threads.

EDIT:

The following example uses Boost threads with ROS. It publishes empty messages to two topics with different rates, which you can easily check with rostopic hz <topic_name>.

#include <ros/ros.h>
#include <std_msgs/Empty.h>
#include <boost/thread/thread.hpp>

void do_stuff(int* publish_rate)
{
  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
  ros::Publisher pub_b = node->advertise<std_msgs::Empty>("topic_b", 10);

  ros::Rate loop_rate(*publish_rate);
  while (ros::ok())
  {
    std_msgs::Empty msg;
    pub_b.publish(msg);
    loop_rate.sleep();
  }
}

int main(int argc, char** argv)
{
  int rate_b = 1; // 1 Hz

  ros::init(argc, argv, "mt_node");

  // spawn another thread
  boost::thread thread_b(do_stuff, &rate_b);

  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
  ros::Publisher pub_a = node->advertise<std_msgs::Empty>("topic_a", 10);

  ros::Rate loop_rate(10); // 10 Hz
  while (ros::ok())
  {
    std_msgs::Empty msg;
    pub_a.publish(msg);
    loop_rate.sleep();

    // process any incoming messages in this thread
    ros::spinOnce();
  }

  // wait the second thread to finish
  thread_b.join();

  return 0;
}
edit flag offensive delete link more

Comments

Thank you i will try it out

elthef gravatar image elthef  ( 2015-09-25 21:34:10 -0500 )edit

Was it working with this?

mrtwister gravatar image mrtwister  ( 2016-03-25 07:30:11 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2015-09-21 08:59:43 -0500

Seen: 17,329 times

Last updated: Sep 21 '15