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

Publishing to a topic via subscriber callback function

asked 2013-04-01 15:39:56 -0500

joy gravatar image

updated 2013-04-02 00:29:29 -0500

felix k gravatar image

Hello, I am wondering if anybody could help me with this problem. I have a listener that just publishes to a topic when another topic is published data, so basically the topic it is listening on gets data published. I have tried putting global variable in the code whose change can map into the main function but ros is not allowing global variables. I also tried to define the nodehandle as global but ros is not allowing this either. (I think before rosinit no ros components will be recognized). My code is in C++. Any help as to what could be done would be really appreciated. I am including a basic skeleton of the code I am trying:

void func_cb(std_msgs type param as defined in ros chatter example)
{
    //*need some code here to publish to a topic*
    //*problem:nodehandle out of scope,cannot define new nodehandle*
}

int main(... )
{
    //ros initilization
    //ros node handle initialization
    //ros subscription initialization
    //callback spinner
    return 0;
}
edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
46

answered 2013-04-01 20:54:02 -0500

updated 2016-07-06 05:37:25 -0500

You could define a class that handles everything and avoid using ugly global variables:

#include <ros/ros.h>

class SubscribeAndPublish
{
public:
  SubscribeAndPublish()
  {
    //Topic you want to publish
    pub_ = n_.advertise<PUBLISHED_MESSAGE_TYPE>("/published_topic", 1);

    //Topic you want to subscribe
    sub_ = n_.subscribe("/subscribed_topic", 1, &SubscribeAndPublish::callback, this);
  }

  void callback(const SUBSCRIBED_MESSAGE_TYPE& input)
  {
    PUBLISHED_MESSAGE_TYPE output;
    //.... do something with the input and generate the output...
    pub_.publish(output);
  }

private:
  ros::NodeHandle n_; 
  ros::Publisher pub_;
  ros::Subscriber sub_;

};//End of class SubscribeAndPublish

int main(int argc, char **argv)
{
  //Initiate ROS
  ros::init(argc, argv, "subscribe_and_publish");

  //Create an object of class SubscribeAndPublish that will take care of everything
  SubscribeAndPublish SAPObject;

  ros::spin();

  return 0;
}
edit flag offensive delete link more

Comments

Thanx Martin...One question though: If I create multiple objects how will ROS handle multiple instances of class publishing in the same topic especially if it is some topic like geomtry_msgs::Twist type? Is it a sequential/interleaved type execution?

joy gravatar image joy  ( 2013-04-02 15:48:57 -0500 )edit

That is a good question. If I am not mistaken, when you create multiple instances of SubscribeAndPublish object, lets say n, then for each message received on the topic "/subscribed_topic" you will generate n messages on the topic "/published_topic". No guarantees about the order though.

Martin Peris gravatar image Martin Peris  ( 2013-04-02 17:06:02 -0500 )edit

So the message is tied with the object id. Thanx so much for clearing that up. :)

joy gravatar image joy  ( 2013-04-05 10:41:22 -0500 )edit

Yeah, I was also going to warn that none the published messages won't actually be sent until after the callback returns. I landed here looking for a workaround.

drewm1980 gravatar image drewm1980  ( 2015-10-20 02:08:04 -0500 )edit

I just wanted to warn you that I think there is a semicolon missing at the end of the class declaration. Thank you for your suggestion!

OMC gravatar image OMC  ( 2016-06-29 08:54:14 -0500 )edit

Thanks @Billie, fixed.

Martin Peris gravatar image Martin Peris  ( 2016-07-06 05:39:50 -0500 )edit

I used this example fpr oublishing velocity from my joystick to my motor. But there is a delay. Maybe I can solve the problem by changing the publsih rate. How can I cahanged the publish rate at this example?

Milliau gravatar image Milliau  ( 2016-12-06 05:45:09 -0500 )edit

You can substitute the call to ros::spin() with: while(true) { ros::Rate(YOUR_DESIRED_RATE).sleep(); ros::spinOnce(); }

Martin Peris gravatar image Martin Peris  ( 2016-12-11 00:40:19 -0500 )edit
1

answered 2020-01-16 01:41:13 -0500

Rufus gravatar image

updated 2020-01-16 02:24:08 -0500

Alternatively, use a lambda, since lambdas can access variables of the same scope by reference / value

ros::Publisher pub = ...;
ros::Subscriber sub = nh.subscribe<my_package::my_message>("/my_topic", 1,
        [&](const my_package::my_message::ConstPtr& msg) //replace & with = to access by value
        {
            pub.publish(...);
        });
edit flag offensive delete link more

Comments

This is an option with recent C++ versions, but note that all the issues with scope still exist (ie: if pub goes out of scope after the lambda has been created, you will get SEGFAULTs.

gvdhoorn gravatar image gvdhoorn  ( 2020-01-16 02:04:11 -0500 )edit

@gvdhoorn This can be mitigated by keeping pub and sub within the same scope and not explicitly deleting pub, am I correct? Also, since the lambda will have undefined reference if pub and sub are in different scopes, this should not occur?

Rufus gravatar image Rufus  ( 2020-01-16 02:23:52 -0500 )edit
0

answered 2017-04-02 23:51:37 -0500

RaoBrother gravatar image
  1. sub_ = n_.subscribe("/subscribed_topic", 1, &SubscribeAndPublish::callback, this);

if u pass &SubscribeAndPublish::callback all so like static , in this conditopn i dont want use static.

Please tell me how to solve the problem .

2 . sub = n.subscribe("/camera/depth_registered/points", 1000, boost::bind(&Example::callBack, this, _1));

this also the same.

Thanks

edit flag offensive delete link more

Question Tools

5 followers

Stats

Asked: 2013-04-01 15:39:56 -0500

Seen: 30,753 times

Last updated: Jan 16 '20