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

[roscpp] unsubscribe within a callback and resubscribe in while(ros::ok)

asked 2014-08-14 14:26:53 -0500

PJ gravatar image

updated 2014-08-14 15:08:08 -0500

bvbdort gravatar image

Hi there, as new to ros and c++, I have a question to ask about unsubscribe and resubscribe. I am working on a multi-quadrotor path planning project and need to define squad leader everytime the team split into new squads. In that case, the squad member will subscribe to its leader for further commanding. But I have trouble on how to unsubscribe old leader's command and resubscribe to a new leader's. Below is the part of code that doing this little function:

ros::Subscriber splitcmd_sub;
// get split command from the leader and determine leader(s) for squad(s)
void getsplitcmd(const geometry_msgs::Point::ConstPtr& msg)

{

//...some code to find out whom to follow

squad_leader_no = ...;

}

int main(int argc, char **argv)
{

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

  ros::NodeHandle n;

  ros::Rate cycle(8); 

while(ros::ok()){

 // ...some other code here

  if(squad_leader_no == 1){splitcmd_sub = n.subscribe("/uav1/split_cmd", 1000, getsplitcmd);}

  if(squad_leader_no == 2){splitcmd_sub = n.subscribe("/uav2/split_cmd", 1000, getsplitcmd);}

  if(squad_leader_no == 3){splitcmd_sub = n.subscribe("/uav3/split_cmd", 1000, getsplitcmd);}

  if(squad_leader_no == 4){splitcmd_sub = n.subscribe("/uav4/split_cmd", 1000, getsplitcmd);}

// ...some code here

  ros::spinOnce();

    cycle.sleep();

  }
  return 0;
}

After a numerous tests, only once I have the subscriber resubscribed. At other times, it just seem not to work at all(no disconnection and reconnection). Also, I have tried splitcmd_sub::shutdown() within the callback, but it just did not work.

I have searched and read a lot of tutorials and questions by other people online, it seems that I will have to use boost::bind if I want to pass parameters from callback to while() in main everytime it receives new messages. Could anybody tell me what to do if I want to unsubscribe a topic and resubscribe to another one at correct times, please? Thanks a lot!

edit retag flag offensive close merge delete

Comments

to be more clear, the publisher split_cmd has been defined and publishing in the same .cpp file

PJ gravatar image PJ  ( 2014-08-14 14:41:07 -0500 )edit

try using if-else to ensure in one loop only one call back and splitcmd_sub::shutdown() inside callback.

bvbdort gravatar image bvbdort  ( 2014-08-14 15:57:43 -0500 )edit

I have tried those, but it did not work

PJ gravatar image PJ  ( 2014-08-14 17:00:51 -0500 )edit

It was my own mistake that caused the problem, and sorry about that! Anyway, thanks a lot for your time!

PJ gravatar image PJ  ( 2014-08-15 17:01:44 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2014-08-15 16:59:58 -0500

PJ gravatar image

Thanks a lot for your time, t.pimentel!!! I have found where I did wrong, and it was a careless mistake. The comparison I made between squad_leader_no and integer value was in different format. Sorry about wasting your time. :/

edit flag offensive delete link more
1

answered 2014-08-14 16:48:00 -0500

t.pimentel gravatar image
subscribe() returns a Subscriber object that you must hold on to until you want to unsubscribe. When all copies of the Subscriber object go out of scope, this callback will automatically be unsubscribed from this topic.

So it should work to just resubscribe to another topic, is squad_leader_no a global variable? Is its value being changed? If it's not working to just resubscribe, you can try to unsubscribe by doing:

splitcmd_sub.shutdown();

Your code would be something like (it's usually better to have local variables, so I changed squad_leader_no to local):

ros::Subscriber splitcmd_sub;
void getsplitcmd(const geometry_msgs::Point::ConstPtr& msg, int *squad_leader_no)
{
  splitcmd_sub.shutdown();
  //...some code to find out whom to follow
  *squad_leader_no = ...;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "mycontrol_4");
  ros::NodeHandle n;
  ros::Rate cycle(8);

  int squad_leader_no = INITIAL_LEADER;

  while(ros::ok()){
   // ...some other code here

    if(squad_leader_no == 1){
      splitcmd_sub = n.subscribe<geometry_msgs::Point>("/uav1/split_cmd", 1000, boost::bind(getsplitcmd, &squad_leader_no, _1) );
    }
    if(squad_leader_no == 2){ repeat }
    if(squad_leader_no == 3){ repeat }
    if(squad_leader_no == 4){ repeat }

    // ...some code here

    ros::spinOnce();
    cycle.sleep();
  }
  return 0;
}
edit flag offensive delete link more

Comments

yes, the squad_leader_no is a global variable so far and its value changes. I will try your code first and let know if the problem has been solved. Thank you.

PJ gravatar image PJ  ( 2014-08-14 16:59:41 -0500 )edit

hi t.pimentel, I have tried boost::bind and defined squad_leader_no as local, but still got the same results, topics were not chosen and resubscribed then. But when I put 'uav1/split_cmd' as initial condition before while(ros::ok()) and remove all the if statements in while(), it could successfully be shut down.

PJ gravatar image PJ  ( 2014-08-14 20:03:20 -0500 )edit

I am wondering if the frequency the loop spinning will be a potential reason causing this problem, like it needs time to proceed received data before subscribing again.

PJ gravatar image PJ  ( 2014-08-14 20:06:28 -0500 )edit

Did you try to use a flag to only enter the if statements if there was a change?

if( squad_leader_no != old_squad_leader_no ) {
    if(squad_leader_no == 1){
        //do something
    }
}
t.pimentel gravatar image t.pimentel  ( 2014-08-15 07:43:32 -0500 )edit

well, it does not help, either. The weird thing is, it could unsubscribe using shutdown() within callbacks and removing all those if statements in while(). But once I wanted it to resubscribe with if statements in while(), it seemed no unsubscribing and resubscribing happened, it just stayed on initial subscription.

PJ gravatar image PJ  ( 2014-08-15 12:27:03 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-08-14 14:26:53 -0500

Seen: 155,254 times

Last updated: Aug 14 '14