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

Can't resubscribe to a topic after shutdown

asked 2022-04-27 12:47:22 -0500

blackdixvery gravatar image

I, I'm having some issues. The code works fine until the shutdown of the subscriber, after that, the specific topics are not resubscribed, so I cannot do anything more.

Ps: the code works fine without the shutdowns, but I want to shutdown the subscribers when I don't need them.

This is my code:

class ObjectDetection
{

public:

  ObjectDetection(ros::NodeHandle *nh)
  {
    nh->getParam("/point_cloud", path_cloud);
    nh->getParam("/image", path_image);
    nh->getParam("/output_cloud", path_outcloud);
    pub_cloud= nh->advertise<sensor_msgs::PointCloud2>(path_outcloud, 1, true);
    subcloud= nh->subscribe(path_cloud, 1, &ObjectDetection::cloud_callback, this);
    image_transport::ImageTransport it(*nh);
    subimage = it.subscribe("/imagetimer", 1, &ObjectDetection::cloud_processing, this);
  }

    //Receive point cloud
  void cloud_callback (const sensor_msgs::PointCloud2& cloud_msg){

   //do stuff

  }

  void cloud_processing(const sensor_msgs::ImageConstPtr& msg)
  {
    //do stuff

    pub_cloud.publish(point_cloud_result);

    subcloud.shutdown();
    subimage.shutdown();

  }

private:
  std::string path_cloud, path_image, path_outcloud;
  ros::Subscriber subcloud;
  ros::Publisher pub_cloud;
  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr primary_cloud;
  image_transport::Subscriber subimage;

};

int main (int argc, char **argv)
{
  ros::init(argc, argv, "ObjectDetectionServer");
  ros::NodeHandle nh;
  ObjectDetection ObjectD= ObjectDetection(&nh);
  ros::spin();
}

Thank you,

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2022-04-28 03:30:57 -0500

Joe28965 gravatar image

I'm going to ask what you expect to happen.

Let's look at your main (where your program starts).

First line, init ros, nothing weird.

Second line, nodehandle, still nothing weird.

Third line, here it gets interesting. You create an object. What does that mean? Answer: You go through the constructor, so let's look at that:

  • It reads some parameters, that's fine.
  • It makes a publisher, great.
  • AND it makes your two subscribers, one with cloud_callback as callback function. The other one with cloud_processing as callback function (This is important, remember this).

And that's it for the third line.

Now let's take a look at the fourth and final line of your main: ros::spin();. A very simple explanation of spin() is that it checks with all its subscribers (2 in your case) if new messages have arrived. It's basically a loop of that one line (line 4). As long as ROS is OK, it will keep looping that one line (check if there are messages and call the callback functions).

However, once the callback function cloud_processing is called even once, you shut your subscribers down.

In other words, you have a spin() that has nothing to do anymore, there are no subscribers to check, because you terminated them. Your object (ObjectD) is never going to call it's constructor again (that's how objects work), so your subscribers will never be started up again.

Hence my original question: What do you expect to happen?

edit flag offensive delete link more

Comments

Thank you for the explanation. Now I understand the problem, I thought after the shutdown in the callback function, the constructor would just create new subscribers.

Is there any way of doing that with a constructor?

blackdixvery gravatar image blackdixvery  ( 2022-04-28 07:53:36 -0500 )edit

What you could do is create an extra function called (for instance) create_subscribers and call that one from the constructor AND another function.

What I don't understand is why you want to shut down the subscribers, or when they should be reactivated.

Joe28965 gravatar image Joe28965  ( 2022-04-28 08:07:05 -0500 )edit
0

answered 2022-04-28 03:49:44 -0500

aarsh_t gravatar image

Referring to the source code

It seem like, It is because Subscriber::shutdown() will call this Subscriber::Impl::unsubscribe(). Which is resetting the nodeHandle with this function at node_handle_.reset();. Hence the re-subscription will not take place until you restart the node.

It is a good idea to use services or actions which can be called based on the requirement. you can get more insights on the ros-service-client that works on request-response model. To get the additional feedback you can use the ros-action-server.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-04-27 12:47:22 -0500

Seen: 85 times

Last updated: Apr 28 '22